Programming Tips

From OpenCircuits
Revision as of 06:52, 26 August 2009 by DavidCary (talk | contribs) (→‎Auto baud rate detection: clarified (I hope))
Jump to navigation Jump to search


Some programming tips for the DsPIC30F 5011 Development Board:

Memory Map for 5011

Table 6.1 Memory Location
Type Start Address End Address Size
Flash 0x000000 0x00AFFF 44K[1]
+--Flash: Reset Vector 0x000000 0x000003 4
+--Flash: Interrupt Vector Table 0x000004 0x00007F 124
+--Flash: Alternate Vector Table 0x000084 0x0000FF 124
+--Flash: User Program 0x000100 0x00AFFF 43.7K
EEPROM 0x7FFC00 0x7FFFFF 1K[2]
Programming Executive 0x800000 0x8005BF 1472
Unit ID 0x8005C0 0x8005FF 64
Config Registers 0xF80000 0xF8000F 16
Device ID 0xFF0000 0xFF0003 4

[1] Each address is 16-bit wide. Every two addresses correspond to a 24-bit instruction. Each even address contains 2 valid bytes; each odd address contains 1 valid byte plus 1 phathom byte.
[2] Each address is 8-bit wide.


Data Location

Table 6.2 Data Location
Type Description Example
_XBSS(N) [1] RAM Data in X-memory, aligned at N, no initilization int _XBSS(32) xbuf[16];
_XDATA(N) [1] RAM Data in X-memory, aligned at N, with initilization int _XDATA(32) xbuf[] = {1, 2, 3, 4, 5};
_YBSS(N) [1] RAM Data in Y-memory, aligned at N, no initilization int _YBSS(32) ybuf[16];
_YDATA(N) [1] RAM Data in Y-memory, aligned at N, with initilization int _YDATA(32) ybuf[16] = {1, 2, 3, 4, 5};
__attribute__((space(const))) Flash ROM data, constant, accessed by normal C
statements, but 32K max.
int i __attribute__((space(const))) = 10;
__attribute__((space(prog))) Flash ROM data, read/write by program space visibility
window (psv)
int i __attribute__((space(prog)));
__attribute__((space(auto_psv))) Flash ROM data, read by normal C statements, write
by accessing psv
int i __attribute__((space(auto_psv)));
__attribute__((space(psv))) Flash ROM data, read/write by (psv) int i __attribute__((space(psv)));
_EEDATA(N) [1] ROM Data in EEPROM, aligned at N, read/write with psv int _EEDATA(2) table[]={0, 1, 2, 3, 5, 8};
_PERSISTENT RAM Data, data remain after reset int _PERSISTENT var1, var2;
_NEAR RAM Data at near section int _NEAR var1, var2;
_ISR Interrupt service rountine void _ISR _INT0Interrupt(void);
_ISRFAST Fast interrupt service rountine void _ISRFAST _T0Interrupt(void);
  1. N must be a power of two, with a minimum value of 2.


Configuration Bits

  • System clock source can be provided by:
  1. Primary oscillator (OSC1, OSC2)
  2. Secondary oscillator (SOSCO and SOSCI) with 32kHz crystal
  3. Internal Fast RC (FRC) oscillator at 7.37MHz (7372800Hz)
  4. Low-Power RC (LPRC) oscillator (Watchdog Timer) at 512 kHz.
  • These clock sources can be incorporated with interal Phase-locked-loop (PLL) x4, x8 or x16 to yield the osciallator frequrence FOSC
  • The system clock is divided by 4 to yield the internal instruction cycle clock, FCY=FOSC/4
  • FRC with PLLx16 is used to achieve FCY=29.49MHz (29491200Hz or 30MIPS)
 //The code (MACRO) below is to be placed at the top of program (before main)
    _FOSC(CSW_FSCM_OFF & FRC_PLL16);
    _FWDT(WDT_OFF);    //Turn off Watchdog Timer
    _FBORPOR(PBOR_ON & BORV_27 & MCLR_DIS & PWRT_16);
    _FGS(CODE_PROT_OFF); //Disable Code Protection


Timer

  • Each timer is 16-bit (i.e. counting from 0 to 65535).
  • Timer 2 and 3 can be incorporated together to form a 32-bit timer.
  • Prescale is the ratio between timer counts and system clock counts. Prescales of 1:1, 1:8, 1:64 and 1:256 are available.
  • Timers may be used to implement free time clock or mesaure time.

Free Time Clock

  • Let required time for ticking be PERIOD.
  • Number of instruction cycles during PERIOD = PERIOD*FCY cycles
  • Using a prescale of 1:x, the timer period count register = # of cycles/x
  • e.g. PERIOD = 10ms; # of cycles = 10ms*30MHz = 300000 cylces; Using 1:64 Prescale, register setting = 300000/64 = 4688
  void time_init(void){
     TMR1 = 0;		// Clear register
     PR1 = 4688;	// Set period
     //============================================================
     _T1IF = 0;		// Clear interrupt flag
     _T1IE = 1;		// Enable interrupts
     //============================================================
     T1CONbits.TCS = 0;		// Use internal clock source
     T1CONbits.TCKPS = 2;	// Prescale Select 1:64
     T1CONbits.TON = 1;		// Start the timer 
  }
  //********************************************************************
  void _ISRFAST _T1Interrupt(void){
     _T1IF = 0;		// Clear interrupt flag
     //Place user code here
  }

Time Measurement

  • To measure the time taken for action(), use the code below:
  unsigned int measure_time(void){	
     PR3 = 0xFFFF;		// Set counter to maximum
     _T3IF = 0;			// Clear interrupt flag
     _T3IE = 0;			// Disable interrupt
     T3CONbits.TON = 1;		// Start the timer, TMR3 count up
     TMR3 = 0;			//Clear TMR3 to start count up
     //====================================================
     //Add code here to wait for something to happen
     action();
     //====================================================
     T3CONbits.TON = 0;	//Stop the timer
     //====================================================
     return (unsigned int) TMR3/FCY;      //TMR/FCY yields the actual time
  }


Interrupt

  • Registers are involved in Interrupts includes:
  1. Interrupt Flag Status (IFS0-IFS2) registers
  2. Interrupt Enable Control (IEC0-IEC2) registers
  3. Interrupt Priority Control (IPC0-IPC10) registers
  4. Interrupt Priority Level (IPL) register
  5. Global Interrupt Control (INTCON1, INTCON2) registers
  6. Interrupt vector (INTTREG) register
  • User may assign priority level 0-7 to a specific interrupt using IPC. Setting priority to 0 disable a specific interrupt. Level 7 interrupt has the highest priority.
  • Current priority level is stored in bit<7:5> of Status Register (SR). Setting Interrupt Priority Level (IPL) to 7 disables all interrupts (except traps).
  • sti() and cli() can be defined to enable and disable global interrupts for time critical functions:
 #define IPL              ( 0x00e0 )
 #define cli()            SR |= IPL    //Set IPL to 7
 #define sti()            SR &= ~IPL   //Set IPL to 0
 //============================================================
 char adc_ioctl(unsigned char request, unsigned char* argp){
   //...
   cli();		//Disable global interrupt
   for(;ch<=argp[0];ch++)
      adc_add_ch(argp[ch]);	//Add adc channels
   sti();		//Enable global interrupt
   //...
   return 0;
 }
  • dsPic30F has an errate note on the Interrupt Controller. When Nested Interrupt is turned on (NSTDIS=0 by default), a high priority interrupt negating a low priority interrupt may result in an Address Error.
  • To work around the problem, it is suggested by Microchip to use the following MACRO to protect:
  1. the clearing of Interrput Flag
  2. the disabling of Interrupt Enable
  3. the lowering of Interrupt Priority
  4. the modification of IPL in Status Register to 1-6
  #define DISI_PROTECT(X)        { \
                                     __asm__ volatile ("DISI #0x1FFF");\
                                     X; \
                                     DISICNT = 0; \
                                 }
  • For example,
  void _ISR _T1Interrupt( void )
  {
      DISI_PROTECT(IFS0bits.T1IF = 0);
      //do something here...
  }


UART

  • 5011 provides two UART channels UxART, for x=1, 2.
  • UxMODE, UxSTA, UxBRG are registers used to set the mode, indicate the status, and set the baud rate respectively.
  • For UART communications compatiable with RS232 standard, an external driver (e.g. MAX3232ESE) is needed.
  • For UART communications compatiable with RS485 standard, an external driver (e.g. DS3695N) is needed.

Auto baud rate detection

  • The method is provided by ingenia bootloader.
  • The PC sends a ASCII character 'U' (0x55) to the target board.
  • On the first rising edge of the start bit, the target board starts the timer.
  • At the fifth rising edge, the timer is stopped, let the count number be t_count.
    • The measured period corresponds to 8 bits transmitted at a baud rate uxbrg.
    _   _   _   _   _   _
  _|S|_|1|_|1|_|1|_|1|_|S|_  (S = Start Bit)
   |               |
   |<------------->|
   Measured Time
  • The relationship between uxbrg and TMR is
  Measured Time (in seconds) = t_count/Fcy
  uxbrg = 1/(Measured Time/8)
        = 8*Fcy/t_count
  • Since UxBRG is computed by:
  UxBRG = (Fcy/(16*Baudrate)) -1
        = (Fcy/(16*8*Fcy/t_count)) -1
        = t_count/128 -1
  • The following is the code for auto baud rate detection for U2ART:
  unsigned int uart2_autobaud(void){
     U2MODEbits.ABAUD = 1;		//Enable Autobaud detect from U2RX (from IC2 if 0)
     U2MODEbits.UARTEN = 1;		//U2ART enable
     //Timer 3 Config==========================================================
     PR3 = 0xFFFF;			// Set counter to maximum
     _T3IF = 0;			// Clear interrupt flag
     _T3IE = 0;			// Disable interrupt
     T3CONbits.TON = 1;		// Start the timer, TMR3 count up
     //Input Capture Config====================================================
     IC2CONbits.ICM = 3;		//Detect rising	
     _IC2IF = 0;			//Clear interrupt flag
     _IC2IE = 0; 			//Disable interrupt
     //Start Auto baud detection===============================================
     unsigned int i=0;
     cli();				//Disable Global Interrupt
     while(!_IC2IF);			//1st rising edge detected
     TMR3 = 0;			//Clear TMR3 to start count up
     _IC2IF = 0;			//Clear interrupt flag
     while(!_IC2IF);			//2nd rising edge detected
     _IC2IF = 0;			//Clear interrupt flag
     while(!_IC2IF);			//3rd rising edge detected
     _IC2IF = 0;			//Clear interrupt flag
     while(!_IC2IF);			//4th rising edge detected
     _IC2IF = 0;			//Clear interrupt flag
     while(!_IC2IF);			//5th rising edge detected
     _IC2IF = 0;			//Clear interrupt flag
     T3CONbits.TON = 0;		//Stop the timer
     sti(); 			//Enable Global Interrupt
     //Compute value for BRG register==========================================
     unsigned int time;
     time = ((TMR3+0x40)>>7)-1;	//+0x40 for rounding
     //========================================================================
     return time;
  }
  • For 30MIP, tested speeds of transmission include 9600bps, 19200bps, 28800bps, 38400bps and 57600bps.

open()

  • The following structures and variables are used as circular buffers for transmit and receive.
  struct UART_Rx{
      unsigned char   wr;
      unsigned char   rd;
  };
  struct UART_Tx{
      unsigned char   wr;                             
      unsigned char   rd;
      unsigned char   tx_complete_flag;
  };
  struct UART_Rx uart_rx;
  struct UART_Tx uart_tx;
  unsigned char uart_rx_buf[MAX_UART_RX_BUF];
  unsigned char uart_tx_buf[MAX_UART_TX_BUF];
  char uart_open()
  {
     uart_rx.wr = 0;
     uart_rx.rd = 0;
     uart_tx.wr = 0;
     uart_tx.rd = 0;
     uart_tx.tx_complete_flag = 1;
     uart2_init();
     return 0;
  }
  void uart2_init(void){
     unsigned int u2brg = 97; 
     #if(AUTO_BAUD_DECT>0)
     u2brg = uart2_autobaud();
     #endif
     U2BRG  = u2brg;					
     //=================================================================
     // Disable U2ART
     U2MODEbits.UARTEN = 0;			//Disable U2ART module
     //=================================================================
     // Configure Interrupt Priority
     _U2RXIF = 0;	//Clear Rx interrupt flags
     _U2TXIF = 0;	//Clear Tx interrupt flags
     _U2RXIE = 1;	//Receive interrupt: 0 disable, 1 enable 
     _U2TXIE = 1;	//Transmit interrupt: 0 disable, 1 enable
     //=================================================================
     // Configure Mode
     //  +--Default: 8N1, no loopback, no wake in sleep mode, continue in idle mode
     //  +--Diable autobaud detect
     //  +--Enable U2ART module
     U2MODEbits.ABAUD = 0;	//Disable Autobaud detect from U2RX 
     U2MODEbits.UARTEN = 1;	//U2ART enable
     //=================================================================
     // Configure Status
     //  +--Default: TxInt when a char is transmitted, no break char
     //  +--Default: RxInt when a char is received, no address detect, clear overflow
     //  +--Enable Transmit
     U2STAbits.UTXEN = 1;	//Tx enable
  }

write()

  • This function writes a series of bytes to the circular buffer and start transmission.
  int uart_write(unsigned char *buf, int count)
  {
     //If transimt has not completed, return busy
     if(uart_tx.tx_complete_flag == 0){
        return -1;            
     }
     else{
        uart_tx.tx_complete_flag = 0;
     }
     int next_data_pos;
     int byte = 0;
     for (; byte<count; byte++) {
        next_data_pos = pre_wr_cir254buf(   (unsigned char)uart_tx.wr, 
                                            (unsigned char)uart_tx.rd, 
                                             MAX_UART_TX_BUF);   
        if (next_data_pos!=255) {
            //Valid data is available
            uart_tx_buf[uart_tx.wr] = (unsigned char) buf[byte];    //copy the char to tx_buf
            uart_tx.wr = next_data_pos;                                     //increment the ptr
        } else break;
     }
     //Raise Interrupt flag to initiate transmission
     _U2TXIF = 1;    //Start interrupt
     return byte;        
  }
  • The interrupt routine reads from the circular buffer and send the data. The uart is opened such that the module will generate an TX Interrupt when it a byte is sent.
  void _ISR _U2TXInterrupt(void){
     DISI_PROTECT(_U2TXIF = 0);		//Clear Interrupt Flag
     unsigned char next_data_pos;
     next_data_pos = pre_rd_cir254buf( (unsigned char)uart_tx.wr,
                                       (unsigned char)uart_tx.rd, 
                                       MAX_UART_TX_BUF);
     if (next_data_pos!= 255) {
        //Valid Data is available to transmit
        U2TXREG = (uart_tx_buf[(unsigned char)uart_tx.rd] & 0xFF);  //send next byte...
        uart_tx.rd = (unsigned char) next_data_pos;    //update rd pointer
     } else {
        //Transimission has completed
       uart_tx.tx_complete_flag = 1;    // change to empty of tx
     }
  }

read()

  • The interrupt routine writes to the circular buffer when space is available.
  void _ISR _U2RXInterrupt(void){
     unsigned char next_data_pos;
     if ( U2STAbits.URXDA ){
        next_data_pos = pre_wr_cir254buf( uart_rx.wr, uart_rx.rd, MAX_UART_RX_BUF);
        if (next_data_pos!=255) {
           //If buffer is not full
           uart_rx_buf[uart_rx.wr] = (unsigned char) U2RXREG; //Read the data from buffer
           uart_rx.wr = next_data_pos;
         } 
         else{
           //When buffer is full, still remove data from register, butthe incoming data is lost
           next_data_pos = (unsigned char) U2RXREG; 			//Read the data from buffer
         }		
     }
     DISI_PROTECT(_U2RXIF = 0);        //Clear the flag
  }
  • This function reads one byte from the circular buffer.
  int uart_read(unsigned char *buf)
  {
     int next_data_pos;
     next_data_pos = pre_rd_cir254buf( uart_rx.wr, uart_rx.rd, MAX_UART_RX_BUF);
     //Copy 1 byte when data is available
     if (next_data_pos!=255) 
     {
        *buf = uart_rx_buf[uart_rx.rd];     //copy the stored data to buf
        uart_rx.rd = next_data_pos;                 //update the ptr
        return 1;
     }
     //No data can be copied
     else
     {
         return 0;
     }      
  }


I2C

  • Two lines are devoted for the serial communication. SCL for clock, SDA for data.
  • Standard communication speed includes
  1. Standard speed mode: 100kHz
  2. Fast speed mode: 400kHz
  3. High speed mode: 3.4MHz
  • dsPIC30f5011 supports standard and fast speed modes. The maximum speed attainable is 1MHz.
  • Pull-up resistors are required for both SCL and SDA. Minimum pull-up resistance is given by:
    Pull-up resistor (min) = (Vdd-0.4)/0.003  ......  [See section 21.8 in Family reference manual]
  • 2.2Kohm is typical for standard speed mode.
  • After initiating a start/stop/restart bit, add a small delay (e.g. no operation) before polling the corresponding control bit (hardware controlled).
  • After sending a byte and receiving an acknowledgement from the slave device, ensure to change to idle state.

open()

  • The following structure is used to record whether special bits are needed to be sent.
  typedef union{
      unsigned char val;
      struct{
          unsigned START:1;       //start
          unsigned RESTART:1;     //restart
          unsigned STOP:1;        //stop
          unsigned NACK:1;        //not acknowledgment
          unsigned :1;
          unsigned :1;
          unsigned :1;
          unsigned :1;    
      }bits;
  } I2C_STATUS;
  static I2C_STATUS i2c_status;   
  • Initializing I2C with default speed I2C_BRG without interrupts.
  void i2c_open(void)
  {
      //Open i2c if not already opened
      if(I2CCONbits.I2CEN == 0)
      {
          _SI2CIF = 0;        //Clear Slave interrupt
          _MI2CIF = 0;        //Clear Master interrupt
          _SI2CIE = 0;        //Disable Slave interrupt
          _MI2CIE = 0;        //Disable Master interrupt
          I2CBRG = I2C_BRG;
          I2CCONbits.I2CEN = 1;   //Enable I2C module 
          i2cIdle();              //I2C bus at idle state, awaiting transimission
          i2c_status.val = 0;     //clear status flags
      }
  }

ioctl()

  • Use this function before read/write to append special bits before or after the data byte.
  char i2c_ioctl(unsigned char request, unsigned char* argp)
  {
      switch(request){
          case I2C_SET_STATUS:
              i2c_status.val = *argp;
              break;
          default:
              return -1;      //request code not recognised   
      }
      return 0;
  }

write()

  • This function sends an 8-bit data using the I2C protocol.
  Mst/Slv    _______ M ____M___ S M ________ 
  SDA (Data)        |S|  data  |A|S|
                    |T|        |C|T|
                    |A|XXXXXXXX|K|P|
  • Use ioctl() to select whether a start/restart/stop bit is required.
  • If slave does not respond after ACK_TIMEOUT, the transmission is considered unsucessful.
  int i2c_write(unsigned char *buf)
  {
      unsigned int count = 0;
      if(i2c_status.bits.START)
      {
          I2CCONbits.SEN = 1;                 
          Nop();                          //A small delay for hardware to respond
          while(I2CCONbits.SEN);          //Wait till Start sequence is completed
      }
      else if(i2c_status.bits.RESTART)
      {
          I2CCONbits.RSEN = 1;                
          Nop();                          //A small delay for hardware to respond
          while(I2CCONbits.RSEN);         //Wait till Start sequence is completed
      }
      I2CTRN = *buf;                  //Transmit register
      while(I2CSTATbits.TBF);         //Wait for transmit buffer to empty
      while(I2CSTATbits.ACKSTAT){
          if(++count > ACK_TIMEOUT){
              //Slave did not acknowledge, byte did not transmit sucessfully, 
              //send stop bit to reset i2c
              I2CCONbits.PEN = 1;
              Nop();                          //A small delay for hardware to respond
              while(I2CCONbits.PEN);          //Wait till stop sequence is completed
              i2cIdle();
              return 0;
          }
      }
      i2cIdle();
      if(i2c_status.bits.STOP)
      {
          I2CCONbits.PEN = 1;
          Nop();                          //A small delay for hardware to respond
          while(I2CCONbits.PEN);          //Wait till stop sequence is completed
          i2cIdle();
      }
      i2c_status.val = 0;             //Clear status
      return 1;
  }

read()

  • This function reads 1 byte from slave using the I2C protocol.
  Mst/Slv     ____ ___S____ M M _____    
  SDA (Data)      |  data  |A|S|
                  |        |C|T|
                  |XXXXXXXX|K|P|
  • Use ioctl() to select whether an ACK/NACK and/or STOP bit is needed to be sent.
  int i2c_read(unsigned char *buf)
  {
      I2CCONbits.RCEN = 1;                    //Enable Receive
      while(I2CCONbits.RCEN);
      I2CSTATbits.I2COV = 0;                  //Clear receive overflow
      *buf = (unsigned char) I2CRCV;          //Access the receive buffer
      I2CCONbits.ACKDT = (i2c_status.bits.NACK)? 1 : 0;
      I2CCONbits.ACKEN = 1;       //Send Acknowledgement/Not Acknowledgement
      i2cIdle();                  //I2C bus at idle state, awaiting transimission
      if(i2c_status.bits.STOP)
      {
          I2CCONbits.PEN = 1;
          Nop();                          //A small delay for hardware to respond
          while(I2CCONbits.PEN);          //Wait till stop sequence is completed
          i2cIdle();
      }
      i2c_status.val = 0;             //Clear status
      return 1;
  }

Example

  Mst/Slv    _______ M ___M___ M S ____M___ S M ___M___ M S ___S____ M ___S____ M M _____ 
  SDA (Data)        |S|       | |A|        |A|R|       | |A|        |A|        |N|S|
                    |T|address|W|C|channelA|C|E|address|R|C| Data H |C| Data L |A|T|
                    |A|1001111|0|K|00010010|K|S|1001111|1|K|10101010|K|10XXXXXX|K|P|
  /*
   * Send start bit, slave address (Write Mode)
   */ 
  status = I2C_START;
  i2c_ioctl(I2C_SET_STATUS, &status);
  data = (unsigned char) I2C_SLAVE_ADDR;
  i2c_write(&data);
  /*
   * Send control byte: Channel select
   */
  data = (unsigned char) ctrl_byte;
  i2c_write(&data);
  /*
   * Send restart bit, slave address (Read Mode)
   */
  status = I2C_RESTART;
  i2c_ioctl(I2C_SET_STATUS, &status);
  data = (unsigned char) (I2C_SLAVE_ADDR|0x01);
  i2c_write(&data);
  /*
   * Receive High Byte with Acknowledgment
   */
  i2c_read(&data);
  usr_data.high = (unsigned char) data;
  /*
   * Receive Low Byte with Not Acknowledgment and stop bit
   */ 
  status = I2C_NACK | I2C_STOP;
  i2c_ioctl(I2C_SET_STATUS, &status);
  i2c_read(&data);
  usr_data.low = (unsigned char) data;


ADC

  • 12-bit ADC: (Max 16 Channels)
  • Allow a maximum of 2 sets of analog input multiplexer configurations, MUX A and MUX B (Normally use one only).
  • A maximum of 200kps of sampling rate when using auto sampling mode.

open()

  • The following variables are required.
  unsigned int adc_buf[ADC_MAX_CH];   //Store most updated data
  volatile unsigned int* ADC16Ptr = &ADCBUF0; //Pointer to ADC register buffer, 
  unsigned char adc_ch_select = 0;   //Pointer to channel to be read from
  unsigned char adc_data_ready = 0;   //Indicate if RAM data is ready for output
  • Configuration is highlighted below.
    • Interrupt: The ADC module will be set to interrupt when the specified channels are updated.
    • I/O: Set the corresponding TRISBX bits (digit i/o config) to input (i.e. = 1), and set corresponding bits in ADPCFG (analog config) to zero.
    • Scanning Mode: Scan mode is used. In this mode, the Sample and Hold (S/H) is switched between the channels specified by ADCSSL (Scan select register).
    • Reference Voltage for S/H: Only MUX A is used. By default, the negative reference voltage of the S/H is connected to VREF-.
    • Settings for ADC Operation: For 200kbps operation, the voltage references for the ADC voltage are connected to VREF+ and VREF-. Scan input is enabled, and the module will generate an interrupt when all selected channels have been scanned.
    • Sampling Rate: TAD refers to the time unit for the ADC clock. To configure the ADC module at 200kbps, the minimum sampling time of 1TAD = 334ns is required. ADCS<5:0> in ADCON3 register is used to set the time, which is given by:
     ADCS<5:0> = 2(TAD/TCY)-1 
               = 2(334e-9/33.34e-9)-1 
               = 19
  char adc_open(int flags)
  {
     // Configure interrupt
     _ADIF = 0;                          //clear ADC interrupt flag
     _ADIE = 1;                          //enable adc interrupt
    // Configure analog i/o  
    _TRISB0 = 1;
    _TRISB1 = 1;    
    ADPCFG = 0xFFFC;                    //Enable AN0 (Vref+) and AN1 (Vref-)
    // Configure scan input channels    
    ADCSSL = 0x0003;    //0 => Skip, 1 => Scan
    // Configure CH0 Sample and Hold for 200kbps
    //  +-- Use MUX A only
    //  +-- Set CH0 S/H -ve to VRef-
    ADCHSbits.CH0NA = 0;
    // ADCCON3:
    //  +--Auto Sample Time = 1TAD
    //  +--A/D Conversion Clock Source = system clock
    //  +--A/D Conversion Clock Select ADCS<5:0>= 2(TAD/TCY)-1
    //      200kbps(Sampling frequency)
    ADCON3bits.SAMC = ADC_ACQ_TIME;     //1TAD for sampling time
    ADCON3bits.ADRC = 0;                //Use system clock
    ADCON3bits.ADCS = ADC_ADCS;         //each conversion requires 14TAD
    // ADCCON2:
    //  +--Default: Use MUX A, No splitting of Buffer
    //  +--Voltage Reference Configuration Vref+ and Vref-
    //  +--Scan Input Selections
    //  +--5 samples between interrupt
    ADCON2bits.VCFG = 3;                //External Vref+, Vref-
    ADCON2bits.CSCNA = 1;               //Scan input
    ADCON2bits.SMPI = 1;                //take 2 samples (one sample per channel) per interrupt
    // ADCCON1:
    //  +--Default: continue in idle mode, integer format
    //  +--Enable ADC, Conversion Trigger Source Auto, Auto sampling on
    ADCON1bits.FORM = 0;                //[0:integer]; [2 fractional]; [3 siged fractional]
    ADCON1bits.SSRC = 7;                //auto covert, using internal clock source
    ADCON1bits.ASAM = 1;                //auto setting of SAMP bit
    ADCON1bits.ADON = 1;                //Turn on module
    return 0;
  }

read()

  • 16 registers (ADCBUF0 -ADCBUF15) are dedicated to store the ADC data between interrupts. However, the data in ADCBUFx does not necessarily correspond to the data taken for channel x. Since the lowest register will always be filled first, when some of the channels are not scanned (i.e. skipped), care must be taken. The following code checks the ADCSSL register for the current scanning channels and moves the data to the corresponding position in *adc_buf.
  void _ISR _ADCInterrupt(void){
     unsigned int channel = 0;
     unsigned int buffer = 0;
     for (; channel<ADC_MAX_CH; channel++)
     {
        if(select(channel))       //Check if channel has been selected
        {
           adc_buf[channel] = ADC16Ptr[buffer];     //Copy data to adc_buf
           buffer++;
        }
     }
     adc_data_ready = 1;
     DISI_PROTECT(_ADIF = 0);  //Clear adc interrupt
  }
  static unsigned char select(unsigned char ch)
  {
      unsigned int mask;
      mask = 0x0001 << ch;
      if(ADCSSL & mask)
          return 1;
      return 0;
  }
  • User can read from the buffer at anytime to get the most updated analog values.
  int adc_read(unsigned int* buf, int count)
  {
     if(adc_data_ready == 1)
     {
        int num_channel = count/2;                  //number of channels to read
        unsigned char channel = adc_ch_select;     //index for adc_buf
        int i = 0;                                  //index for buf
        while(i<num_channel && channel<ADC_MAX_CH)
        { 
           //Loop only for specified number of channel or all channels 
           buf[i++] = adc_buf[channel++];      //use data in local buffer
           while(select(channel)==0)
           {  //increment to next valid channel
              channel++;                  
              if(channel >= ADC_MAX_CH) break;
           }
        }
       return 2*i;
     }
     return -1;
  }

ioctl()

  • This function is used to add or remove channels from the ADC scanning process.
  char adc_ioctl(unsigned char request, unsigned char* argp)
  {
      switch(request)
      {
          case ADC_ADD_CH:
              //ADD channels to current set==========================
              cli();                      //Disable global interrupt
              if(select(argp[0]) == 0){   //If channel not in scan list
                  adcAdd(argp[0]);            //Add individual channel to scan list
                  adc_data_ready = 0;         //First data not ready yet, until interrupt occurs
              }
              adc_ch_select = argp[0];    //Select current channel for reading
              sti();                      //Enable global interrupt
              break;
          case ADC_RM_CH:
              //REMOVE channels from current set==========================
              cli();                  //Disable global interrupt
              if(select(argp[0])){    //If channel in scan list       
                  adcRm(argp[0]);             //Remove individual channel
                  adc_ch_select = 0;          //Reset to AN0
              }
              sti();                  //Enable global interrupt
              break;
          default:
              return -1;      //request code not recognised   
      }
      return 0;
  }
  • Channels may be added or removed by changing _TRISBX, ADPCFG, ADCSSL and ADCON2bits.SMPI.
  void adc_add_ch(unsigned char ch){
     unsigned int mask;
     mask = 0x0001 << ch;
     TRISB = TRISB | mask;
     ADCSSL = ADCSSL | mask;		 
     ADPCFG = ~ADCSSL;
     ADCON2bits.SMPI++;	//take one more sample per interrupt
  }
  void adc_rm_ch(unsigned char ch){
     unsigned int mask;
     mask = 0x0001 << ch;
     ADPCFG = ADPCFG | mask;
     ADCSSL = ~ADPCFG;
     ADCON2bits.SMPI--;	//take one less sample per interrupt
  }


EEPROM

  • 5011 has 1024 bytes of EEPROM, readable and writable under normal voltage (5V).
  • To use, declare:
 unsigned char _EEDATA(2) eeData[1024]={ 0x00, 0x00, 0x00, 0x00, .... }
 unsigned int byte_pointer = 0;

lseek()

  • This function moves the pointer to the desired position before a reading/writing operation is performed.
  int eeprom_lseek(int offset, unsigned char whence){
     byte_pointer = offset;
     return byte_pointer;
  }

read()

  • This function read count bytes from the eeprom.
  int eeprom_read(unsigned char* buf, int count){
     int i=0;
     for(; i<count && byte_pointer < 1024; i++){
        readEEByte( __builtin_tblpage(eeData), 
                    __builtin_tbloffset(eeData) + byte_pointer, 
                    &buf[i]);
        byte_pointer++;		//Update global pointer
     }
     return i;	//read i bytes successful	
  }
  • readEEByte() is implemented in assembly code as follows:
  .global _readEEByte
  _readEEByte:
     push      TBLPAG		;w0 = base of eeData
     mov       w0, TBLPAG	;w1 = offset for eeData in byte
     tblrdl.b  [w1], [w2]	;w2 = pointer to user buffer
     pop     	TBLPAG
     return

write()

  • This function write count bytes to eeprom.
  int eeprom_write(unsigned char* buf, int count){
     char isOddAddr = byte_pointer%2;	//current address is odd
     char isOddByte = count%2;		//number of bytes to write is odd
     //=================================================================
     unsigned int word_offset = byte_pointer>>1; //div by 2 and round down
     int max_write;
     max_write = (isOddAddr == 0 && isOddByte == 0) ? (count>>1) : (count>>1)+1;
     //=================================================================
     unsigned int word_data;	//Store word to be written
     int byte_wr = 0;		//number of bytes written, i.e buffer pointer
     int i = 0;
     //=================================================================
     for(; i<max_write && word_offset<512; i++, word_offset++){
        if(i==0 && isOddAddr){
           //First byte not used
           //============================================save first byte
           readEEByte( __builtin_tblpage(eeData), 
                       __builtin_tbloffset(eeData) + byte_pointer - 1,
                       &word_data);
           //===========================================================
           word_data = ((unsigned int)buf[0] << 8) + (0xFF & word_data);
           byte_wr++;				//Update buffer pointer
           byte_pointer++;			//Update global pointer
         } else if(i==max_write-1 && ((isOddAddr && sOddByte==0)||(isOddAddr==0 && isOddByte))){
           //Last byte not used
           //=============================================save last byte
           readEEByte(	__builtin_tblpage(eeData), 
                       __builtin_tbloffset(eeData) + byte_pointer + 1,
                       &word_data);
           //============================================================
           word_data = (word_data << 8) + buf[byte_wr];
           byte_wr++;				//Update buffer pointer
           byte_pointer++;			//Update global pointer
         } else{
           //Both bytes valid
           word_data = ((unsigned int)buf[byte_wr+1] << 8) + buf[byte_wr];
           byte_wr+=2;				//Update buffer pointer
           byte_pointer+=2;		//Update global pointer
         }
      //==================================================================
      eraseEEWord( __builtin_tblpage(eeData), 
                   __builtin_tbloffset(eeData) + 2*word_offset);
      writeEEWord( __builtin_tblpage(eeData), 
                   __builtin_tbloffset(eeData) + 2*word_offset,
                   &word_data);
      //==================================================================
      }
      return byte_wr;		//No. of byte written
  }
  • eraseEEWord and writeEEWord are implemented in assembly.
  .global _eraseEEWord
  _eraseEEWord:
     push   TBLPAG				
     mov    w0, NVMADRU	;w0 = base of eeData
     mov    w1, NVMADR		;w1 = offset for eeData in word
     mov    #0x4044, w0			
     mov    w0, NVMCON		;Set to erase operation
     push   SR			;Disable global interrupts
     mov    #0x00E0, w0
     ior    SR
     mov    #0x55, w0 		;Write the KEY sequence
     mov    w0, NVMKEY
     mov    #0xAA, w0			
     mov    w0, NVMKEY
     bset   NVMCON, #15	;Start the erase cycle, bit 15 = WR
     nop
     nop
 L1: btsc   NVMCON, #15	;while(NVMCONbits.WR)
     bra    L1
     clr    w0
     pop    SR			;Enable global interrupts
     pop    TBLPAG
     return
 .global _writeEEWord
 _writeEEWord:
     push   TBLPAG		;w0 = base of eeData
     mov    w0, TBLPAG		;w1 = offset for eeData in byte
     tblwtl [w2], [w1]		;w2 = pointer to user buffer
     mov    #0x4004, w0        ;Set to write operation
     MOV    w0, NVMCON
     push   SR			;Disable global interrupts
     mov    #0x00E0, w0
     ior    SR
     mov    #0x55, w0 		;Write the KEY sequence
     mov    w0, NVMKEY
     mov    #0xAA, w0			
     mov    w0, NVMKEY
     bset   NVMCON, #15	;Start the erase cycle, bit 15 = WR
     nop
     nop
 L2: btsc   NVMCON, #15	;while(NVMCONbits.WR)
     bra    L2
     clr    w0
     pop    SR			;Enable global interrupts
     pop    TBLPAG
     return


Simple PWM (Output Compare Module)

  • The PWM module consists of 8 channels using the output compare module of dsPic.
  • These channels are locate at pin 46 (OC1), 49 (OC2), 50 (OC3), 51 (OC4), 52 (OC5), 53 (OC6), 54 (OC7), 55 (OC8). These pins are shared with port D.
  • The range of PWM freqeuencies obtainable is 2Hz to 15MHz (See Figure 6.3). Suggested range of operation is 2Hz to 120kHz. The relationship between resolution r and PWM frequency fPWM is given by:
        fPWM = fCY/(Prescale*10rlog(2))
Table 6.3 Relationship of Resolution and PWM Frequency
Resolution (bit) Prescale=1 Prescale=8 Prescale=64 Prescale=256
1 15,000,000 1,875,000 234,375 58,594
2 7,500,000 937,500 117,188 29,297
3 3,750,000 468,750 58,594 14,648
4 1,875,000 234,375 29,297 7,324
5 937,500 117,188 14,648 3,662
6 468,750 58,594 7,324 1,831
7 234,375 29,297 3,662 916
8 117,188 14,648 1,831 458
9 58,594 7,324 916 229
10 29,297 3,662 458 114
11 14,648 1,831 229 57
12 7,324 916 114 29
13 3,662 458 57 14
14 1,831 229 29 7
15 916 114 14 4
16 458 57 7 2

open()

  • A timer (either Timer 2 or 3) is needed to determine the pwm period. The following code uses timer 2 for all 8 channels.
 void pwm_open(void){
   OC1CON = 0;	OC2CON = 0; //Disable all output compare modules
   OC3CON = 0; OC4CON = 0;
   OC5CON = 0; OC6CON = 0;
   OC7CON = 0; OC8CON = 0;
   //============================================================
   TMR2 = 0;		// Clear register
   PR2 = 0xFFFF;	// Set to Maximum
   //============================================================
   _T2IF = 0;		// Clear interrupt flag
   _T2IE = 0		// Enable interrupts
   //============================================================
   T2CONbits.TCS = 0;		// Use internal clock source
   T2CONbits.TCKPS = 0;	// Prescale Select 1:1
   //============================================================
   T2CONbits.TON = 1;		// Start the timer 	
 }

ioctl()

  • User should select the channel and set the pwm period using the functions below before issuing the duty cycle:
 char pwm_ioctl(unsigned char request, unsigned long* argp){
   unsigned int value;
   unsigned char mask;
   switch(request){
     case PWM_SET_PERIOD:
       return setPeriodNPrescale(argp[0]);
     case PWM_SELECT_CH:
       pwm_channel = argp[0];
       mask = 0x01 << pwm_channel;
       pwm_status = pwm_status | mask;
           return 0;
     default:
           return -1;
   }
 }
 char setPeriodNPrescale(unsigned long value_ns){
   unsigned long ans;
   unsigned long long numerator = (unsigned long long)value_ns*SYSTEM_FREQ_MHZ;
   int index= -1;
   unsigned long denominator;
   //-------------------------------------------------
   do{
       denominator = (unsigned long)1000*pwm_prescale[++index];
       ans = (unsigned long)(((long double)numerator/denominator) + 0.5) - 1; //round to nearest int
   } while(ans > 0x0000FFFF && index < 3);
   //-------------------------------------------------
   if(ans > 0x0000FFFF)
       return -1;
   //-------------------------------------------------
   T2CONbits.TON = 0;		// Turn off the timer
   T2CONbits.TCKPS = index;	// Change prescale factor
   PR2 = (unsigned int) ans;	// Set to Maximum
   T2CONbits.TON = 1;		// Turn on the timer 	
   //-------------------------------------------------
   return 0;
 }

write()

  • User can change the duty cycle using the following functions
 int pwm_write(unsigned long* buf){
   if((pwm_status & (0x01 << pwm_channel)) == 0){
       return -1;		//Channel has not been enabled
   }
   switch(pwm_channel){
       case 0:
           OC1RS = calcDCycle(buf[0]); OC1R = OC1RS; 
           OC1CONbits.OCM = 6; //Simple PWM, Fault pin disabled
           break;
       case 1:
           OC2RS = calcDCycle(buf[0]);	OC2R = OC2RS; 
           OC2CONbits.OCM = 6; //Simple PWM, Fault pin disabled
           break;
       ...
       case 7:
           OC8RS = calcDCycle(buf[0]); OC8R = OC8RS; 
           OC8CONbits.OCM = 6; //Simple PWM, Fault pin disabled
           break;	
       default:
           return -1;
   }
   return 4;
}
 unsigned int calcDCycle(unsigned long value_ns){
   unsigned long long numerator = (unsigned long long)value_ns*SYSTEM_FREQ_MHZ;
   unsigned int index = T2CONbits.TCKPS;
   unsigned long denominator = (unsigned long)1000*pwm_prescale[index];
   return (unsigned int)(((long double)numerator/denominator) + 0.5) - 1; //round to nearest int
 }

Propagration Delay

  • PWM channels sharing the same timer will have their PWM signals synchronised (i.e. the HIGH state of the duty cycle are all triggered together).
  • To introduced delay to the PWM signals, the signal from selected channels may be made to pass through a series of inverters (e.g. 74HC14D). This adds propagation delay to the signal.
  • However, as propagration delay of logic gates depends on applied voltage, temperature and load capacitance, the accuracy is low and performance is poor. For accurate delay, delay lines may be used, but they are expensive.
Table 6.4 Propagation Delay of Philips 74HC14D[1], [2]
3.3V 5.0V
Number of Gates A B C A B C
2 21ns (10.5) 23ns (11.5) 22ns (11.0) 15ns (7.5) 14ns (7.0) 14ns (7.0)
4 45ns (11.3) 46ns (11.5) 46ns (11.5) 30ns (7.5) 30ns (7.5) 30ns (7.5)
6 69ns (11.5) 70ns (11.7) 72ns (12.0) 45ns (7.5) 46ns (7.7) 47ns (7.8)

[1] Data in specification for 4.5V: Typical 15ns, Maximum 25ns
[2] Data in specification for 6.0V: Typical 12ns, Maximum 21ns


DSP Library

  • Library functions in <dsp.h> include the following categories:
  1. Vector
  2. Window
  3. Matrix
  4. Filtering
  5. Transform
  6. Control

Data Types

  • Signed Fractional Value (1.15 data format)
    • Inputs and outputs of the dsp functions adopt 1.15 data format, which consumes 16 bits to represent values between -1 to 1-2-15 inclusive.
    • Bit<15> is a signed bit, positive = 0, negative = 1.
    • Bit<14:0> are the exponent bits e.
    • Positive value = 1 - 2-15*(32768 - e)
    • Negative value = 0 - 2-15*(32768 - e)
  • 40-bit Accumulator operations (9.31 data format)
    • The dsp functions use the 40 bits accumalators during arithmatic calculations.
    • Bit<39:31> are signed bits, positive = 0x000, negative = 0x1FF.
    • Bit<30:0> are exponent bits.
  • IEEE Floating Point Values
    • Fractional values can be converted to Floating point values using: fo = Fract2Float(fr); for fr = [-1, 1-2-15]
    • Floating point values can be converted to Fractional values using: fr = Float2Fract(fo); or fr = Q15(fo); for fo = [-1, 1-2-15]
    • Float2Fract() is same as Q15(), except having saturation control. When +ve >= 1, answer = 215-1 = 32767 (0x7FFF). When -ve < -1, answer = -215 = -32767 (0x8000)


Build-in Library

  • Some assembler operators can only be accessed by inline assembly code, for example,
  1. Manuipulation of accumulators A and B (add, sub, mul, divide, shift, clear, square)
  2. Bit toggling
  3. Access to psv (program space visiblity) page and offset
  4. Access to table instruction page and offset
  • Built-in functions are written as C-like function calls to utilize these assembler operators.


Address Error

  • Possible Causes
    • Misuse of C pointers