boot.c
Go to the documentation of this file.
00001 //
00002 // © 2010 Shadow Robot Company Limited.
00003 //
00004 // FileName:        boot.c
00005 // Dependencies:    
00006 // Processor:       PIC18
00007 // Compiler:        MPLAB® C18 
00008 //
00009 //  +-------------------------------------------------------------------------------+
00010 //  | This file is part of The Shadow Robot PIC18 firmware code base.               |
00011 //  |                                                                               |
00012 //  | It is free software: you can redistribute it and/or modify                    |
00013 //  | it under the terms of the GNU General Public License as published by          |
00014 //  | the Free Software Foundation, either version 3 of the License, or             |
00015 //  | (at your option) any later version.                                           |
00016 //  |                                                                               |
00017 //  | It is distributed in the hope that it will be useful,                         |
00018 //  | but WITHOUT ANY WARRANTY; without even the implied warranty of                |
00019 //  | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the                 |
00020 //  | GNU General Public License for more details.                                  |
00021 //  |                                                                               |
00022 //  | You should have received a copy of the GNU General Public License (gpl.txt)   |
00023 //  | along with this code repository. The text of the license can be found         |
00024 //  | in Pic32/License/gpl.txt. If not, see <http://www.gnu.org/licenses/>.         |
00025 //  +-------------------------------------------------------------------------------+
00026 //
00027 //
00028 // This file implements the bulk of the CAN bootloader.
00029 //
00030 
00031 #include "basics.h"
00032 #include <p18f2580.h>
00033 
00034                                             // These are values for setting up the CAN baud rate and timings
00035                                             // -------------------------------------------------------------
00036 #define CAN_SJW         0x01                // range 1..4       Synchronisation Jump Width
00037 #define CAN_BRP         0x02                // range 1..64      Baud Rate Prescaler
00038 #define CAN_PHSEG1      0x01                // range 1..8       Phase Segment 1
00039 #define CAN_PHSEG2      0x02                // range 1..8       Phase Segment 2
00040 #define CAN_PROPSEG     0x06                // range 1..8       Propagation Segment
00041 #define CAN_SAM         0x00                // range 0 or 1     Sample type (0==once, 1==three times)
00042 #define CAN_SEG2PHTS    0x00                // range 0 or 1     
00043 
00044 #define CAN_CONFIG_MODE     0b10000000      // 
00045 #define CAN_LISTEN_MODE     0b01100000
00046 #define CAN_LOOPBACK_MODE   0b01000000
00047 #define CAN_DISABLE_MODE    0b00100000
00048 #define CAN_NORMAL_MODE     0b00000000
00049 
00050 #define RD          0
00051 #define RXFUL       7
00052 #define TXREQ       3
00053 #define EEPGD       7
00054 #define WREN        2
00055 #define WR          1
00056 #define CFGS        6
00057 #define GIE         7
00058 
00059 
00062 typedef enum
00063 {
00064     WRITE_FLASH_DATA_COMMAND      = 0x00,
00065     READ_FLASH_COMMAND            = 0x01,
00066     ERASE_FLASH_COMMAND           = 0x02,
00067     RESET_COMMAND                 = 0x03,
00068     READ_VERSION_COMMAND          = 0x04,
00069     WRITE_FLASH_ADDRESS_COMMAND   = 0x05,
00070     MAGIC_PACKET                  = 0x0A
00071 }BOOTLOADER_COMMAND;
00072 
00073 typedef enum
00074 {
00075     ECAN_RX_OVERFLOW     = 0b00001000,
00076     ECAN_RX_INVALID_MSG  = 0b00010000,
00077     ECAN_RX_XTD_FRAME    = 0b00100000,
00078     ECAN_RX_RTR_FRAME    = 0b01000000,
00079     ECAN_RX_DBL_BUFFERED = 0b10000000
00080 
00081 } ECAN_RX_MSG_FLAGS;
00082 
00083 
00084 
00086 struct CANmsg 
00087 {
00088         int16u messageID;
00089         union msg_data
00090         {
00091           int8u byte[8];
00092           int16u word[4];
00093           int32u dword[2];
00094               int64u qword;
00095         } d;
00096         int8u length;
00097         ECAN_RX_MSG_FLAGS flags;
00098 };
00099 struct CANmsg CanMsgT;                          
00100 struct CANmsg CanMsgR;                          
00101 
00102 
00103 int8u motor_id = 0xFF;                          
00104 int8u position = 0x00;                          
00105 
00106 
00107 
00113 #pragma code VIntH=0x0008
00114 void VIntH(void)
00115 {
00116     _asm
00117         goto 0x0270 
00118     _endasm
00119 }
00120 #pragma code
00121 
00122 
00128 #pragma code VIntL=0x000e
00129 void VIntL(void)
00130 {
00131     _asm
00132         goto 0x0280
00133     _endasm
00134 }
00135 #pragma code
00136 
00137 
00138 
00139 
00140 
00141 
00149 static int8u read_eeprom(int8u address)
00150 {
00151     EECON1 = 0;
00152     EEADR = address;
00153     //EEADRH = 0xff; FIXME: why is this in the microchip code ?
00154     EECON1 |= (1 << RD);
00155     return EEDATA;
00156 }
00157 
00158 
00166 static int8u we_should_boot(void)
00167 {
00168     return (read_eeprom(0xFF) != 0xFF);
00169 }
00170 
00171 
00175 typedef enum
00176 {
00177     SYNC_JUMP_WIDTH_1X = 0b00000000,
00178     SYNC_JUMP_WIDTH_2X = 0b01000000,
00179     SYNC_JUMP_WIDTH_3X = 0b10000000,
00180     SYNC_JUMP_WIDTH_4X = 0b11000000
00181 }SYNC_JUMP_WIDTH_VALUES;
00182 
00183 
00187 typedef enum
00188 {
00189     SEG2PHTS_FREE = 0b10000000,
00190     SEG2PHTS_CALC = 0b00000000
00191 }SEG2PHTS_VALUES;
00192 
00193 
00196 typedef enum
00197 {
00198     SAMPLE_ONCE   = 0b00000000,
00199     SAMPLE_THRICE = 0b01000000
00200 }SAMPLE_TIMES_VALUES;
00201 
00202 
00205 typedef enum
00206 {
00207     CAN_WAKE_ENABLE  = 0b00000000,
00208     CAN_WAKE_DISABLE = 0b10000000
00209 }CAN_WAKE_VALUES;
00210 
00213 typedef enum
00214 {
00215     CAN_MODE_LEGACY           = 0b00000000,
00216     CAN_MODE_ENHANCED_LEGACY  = 0b01000000,
00217     CAN_MODE_ENHANCED_FIFO    = 0b10000000
00218 }CAN_MODE_VALUES;
00219 
00222 typedef enum
00223 {
00224     RECEIVE_ALL_MESSAGES      = 0b01100000,
00225     RECEIVE_EXTENDED_MESSAGES = 0b01000000,
00226     RECEIVE_STANDARD_MESSAGES = 0b00100000
00227 }RECEIVE_BUFFER_MODE_VALUES;
00228 
00231 typedef enum
00232 {
00233     CANTX_DRIVE_VDD           = 0b00100000,
00234     CANTX_DRIVE_TRI_STATE     = 0b00000000
00235 }CANTX_DRIVE_VALUES;
00236 
00237 
00238 // The following #defines are used to configure the CAN bus,
00239 // Specifically the speed and timing, among other things
00240 #define BAUD_RATE_PRESCALER                             1
00241 #define SYNC_JUMP_WIDTH                SYNC_JUMP_WIDTH_2X
00242 #define SEG2PHTS                            SEG2PHTS_FREE
00243 #define SAMPLE_TIMES                        SAMPLE_THRICE
00244 #define PHASE_SEGMENT_1                                 6
00245 #define PHASE_SEGMENT_2                                 6
00246 #define PROPAGATION_SEGMENT                             7
00247 #define CAN_MODE                          CAN_MODE_LEGACY
00248 #define RECEIVE_BUFFER_MODE     RECEIVE_STANDARD_MESSAGES
00249 #define CANTX_DRIVE                       CANTX_DRIVE_VDD
00250 
00251 
00256 static void can_init(void)
00257 {
00258 
00259     while ((CANSTAT & 0b11100000) != CAN_CONFIG_MODE)       // Enter CAN Config mode
00260         CANCON = CAN_CONFIG_MODE;
00261 
00262     BRGCON1 = SYNC_JUMP_WIDTH | (BAUD_RATE_PRESCALER-1);                                        //0x41;
00263     BRGCON2 = SEG2PHTS | SAMPLE_TIMES | ((PHASE_SEGMENT_1-1)<<3) | (PROPAGATION_SEGMENT-1);     //0x0B;
00264     BRGCON3 = CAN_WAKE_DISABLE | (PHASE_SEGMENT_2-1);                                           //0x82;
00265 
00266     
00267     ECANCON = CAN_MODE;                    
00268     RXB1CON = RECEIVE_BUFFER_MODE;
00269     RXB0CON = RECEIVE_BUFFER_MODE;
00270     CIOCON  = CANTX_DRIVE;
00271 
00272     RXF0SIDH = 0b11000000 | (motor_id << 2);                // This mask/filter is used to accept bootloader messages 0b11MMMMxxxxx
00273     RXF0SIDL = 0;                                           // 
00274     RXF1SIDH = 0b11000000 | (motor_id << 2);                // 
00275     RXF1SIDL = 0;                                           // 
00276     RXM0SIDH = 0b11111100;                                  // set mask to                                            0b11111100000
00277     RXM0SIDL = 0;                                           // 
00278 
00279     RXF2SIDH = 0;                                           // This mask/filter is not used.
00280     RXF2SIDL = 0;                                           // 
00281     RXF3SIDH = 0;                                           // 
00282     RXF3SIDL = 0;                                           // 
00283     RXF4SIDH = 0;                                           // 
00284     RXF4SIDL = 0;                                           // 
00285     RXM1SIDH = 0b11111111;                                  // 
00286     RXM1SIDL = 0b11100000;                                  //  
00287 
00288     TRISB &= ~(1 << 2);                                     // set CAN TX pin to output mode
00289 
00290     while ((CANSTAT & 0b11100000) != CAN_NORMAL_MODE)       // Enter Normal Mode
00291         CANCON = CAN_NORMAL_MODE;
00292 }
00293 
00294 
00295 
00300 static void sendCanMsg(void)
00301 {
00302     TXB0SIDL = ((CanMsgT.messageID << 5) & 0xff);           // Load the message into the registers
00303     TXB0SIDH = ((CanMsgT.messageID >> 3) & 0xff);
00304     TXB0DLC  = CanMsgT.length;
00305     TXB0D0   = CanMsgT.d.byte[0];
00306     TXB0D1   = CanMsgT.d.byte[1];
00307     TXB0D2   = CanMsgT.d.byte[2];
00308     TXB0D3   = CanMsgT.d.byte[3];
00309     TXB0D4   = CanMsgT.d.byte[4];
00310     TXB0D5   = CanMsgT.d.byte[5];
00311     TXB0D6   = CanMsgT.d.byte[6];
00312     TXB0D7   = CanMsgT.d.byte[7];
00313 
00314     TXB0CON |= (1 << TXREQ);                                // Now transmit that message
00315 }
00316 
00317 
00323 static void erase_flash(void)
00324 {
00325     overlay int16u address = 0;         // address we're erasing
00326 
00327     address = 0x04c0;                   // user application start address
00328                                         // 0x7dc0 is the start of debugger code
00329 
00330     while (address < 0x7dc0)            // and we don't want to erase debugger code
00331     {
00332         TBLPTR  = address;
00333         TBLPTR &= 0xFFFFE0;
00334         
00335         EECON1 |=128;                   // point to Flash program memory
00336         EECON1 &= ~64;                  // access Flash program memory
00337         EECON1 |= 4;                    // enable write to memory
00338         EECON1 |= 16;                   // enable Row Erase operation
00339         INTCON &= ~128;                 // disable interrupts
00340         EECON2 = 0x55;
00341         EECON2 = 0xaa;
00342         EECON1 |= 2;                    // start erase (CPU stall)
00343         
00344         while (EECON1 & 2)              // Wait for stuff being written
00345         {
00346         }
00347 
00348         INTCON |= 128;                  // enable interrupts
00349         address += 64;
00350     }   
00351 }
00352 
00353 
00354 
00360 static void read_flash(void)
00361 {
00362     overlay int8u i = 0;
00363 
00364     TBLPTRL = CanMsgR.d.byte[0];
00365     TBLPTRH = CanMsgR.d.byte[1];
00366     TBLPTRU = CanMsgR.d.byte[2];
00367 
00368     while (i < 8)
00369     {
00370         _asm
00371             TBLRDPOSTINC
00372         _endasm
00373         CanMsgT.d.byte[i++] = TABLAT;
00374     }
00375     CanMsgT.messageID = CanMsgR.messageID | 0x10; // We set the "ACK" bit in the SID
00376     CanMsgT.length    = 8;
00377     sendCanMsg();
00378 }
00379 
00380 
00381 
00386 static void acknowledge_packet(void)
00387 {
00388     CanMsgT = CanMsgR;
00389     CanMsgT.messageID |= 0x10;          // Just add the ACK bit
00390     sendCanMsg();                       // And send the message back
00391 }
00392 
00393 
00394 
00399 static void write_flash_address(void)
00400 {
00401     position = 0;                       // resets the position to 0, we are starting to write a 32 bytes block
00402     TBLPTRU = CanMsgR.d.byte[2];
00403     TBLPTRH = CanMsgR.d.byte[1];
00404     TBLPTRL = CanMsgR.d.byte[0];
00405 }
00406 
00407 
00408 
00418 static void write_flash_data(void)
00419 {
00420     int8u i;
00421     
00422     for (i=0 ;i<8; ++i)                                 // Put 8 more bytes in the buffer
00423     {
00424         TABLAT = CanMsgR.d.byte[i];
00425         _asm
00426             TBLWTPOSTINC
00427         _endasm
00428     }
00429 
00430     position += 8;                                      // We just buffered 8 more bytes
00431 
00432     if (position == 32)                                 // If we have buffured a 32 bytes block, we can start the wrtting procedure
00433     {
00434         _asm
00435             TBLRDPOSTDEC                                // We do a TBLRDPOSTDEC in order for the TBLPTR addressing register to stay in the range of the 32 bytes
00436         _endasm                                         // block we are writting, this is necessary because there has been one extra unneeded TBLWTPOSTINC during
00437                                                         // the previous loop. If we don't do that, the block will be written over the next block, so 32 bytes after
00438                                                         // the address provided by the previous WRITE_FLASH_ADDRESS command.
00439 
00440         EECON1 |= ((1 << EEPGD) | (1 << WREN));         // point to Flash program memory & enable write to memory
00441         EECON1 &= ~(1 << CFGS);                         // access Flash program memory
00442         INTCON &= ~(1 << GIE);                          // disable interrupts
00443         EECON2 = 0x55;                                  // magic enable
00444         EECON2 = 0xaa;
00445         EECON1 |= (1 << WR);                            // starts the actual writting (CPU stall)
00446         INTCON |= (1 << GIE);                           // re-enable interrupts
00447         EECON1 &= ~(1 << WREN);                         // disable write to memory
00448         position = 0;                                   // reset the position to 0, we just finished a 32 bytes block
00449     }
00450 }
00451 
00452 
00453 
00463 static void write_eeprom(void)
00464 {
00465     EEADR   = 0xff;                                     // EEPROM address to write to 
00466     EEDATA  = 0x42;                                     // Something != than 0xFF it's the data to be written
00467     EECON1 &= ~( (1 << EEPGD) | (1 << CFGS) );          // we select EEPROM memory
00468     EECON1 |=    (1 << WREN);                           // enable write to memory
00469     INTCON &= ~  (1 << GIE );                           // disable interrupts
00470 
00471     EECON2  = 0x55;                                     // magic enable
00472     EECON2  = 0xaa;
00473     EECON1 |= (1 << WR);                                // do the write
00474 
00475     while (EECON1 & (1 << WR))                          // wait for the write to finish
00476     {
00477     }
00478 
00479     INTCON |=  (1 << GIE );                             // enable back interrupts
00480     EECON1 &= ~(1 << WREN);                             // disable write to memory
00481     
00482 }
00483 
00484 
00485 
00493 static void handle_can_msg(void)
00494 {
00495     if ( (RXB0CON & (1 << RXFUL) ) )                    // This checks if we received a CAN message
00496     {                                                   // We just received a CAN message, we put it in our CanMsgR reception struct
00497         CanMsgR.messageID   = RXB0SIDH;
00498         CanMsgR.messageID <<= 3;
00499         CanMsgR.messageID  |= RXB0SIDL >> 5;
00500         CanMsgR.length      = RXB0DLC;
00501         CanMsgR.d.byte[0]   = RXB0D0;
00502         CanMsgR.d.byte[1]   = RXB0D1;
00503         CanMsgR.d.byte[2]   = RXB0D2;
00504         CanMsgR.d.byte[3]   = RXB0D3;
00505         CanMsgR.d.byte[4]   = RXB0D4;
00506         CanMsgR.d.byte[5]   = RXB0D5;
00507         CanMsgR.d.byte[6]   = RXB0D6;
00508         CanMsgR.d.byte[7]   = RXB0D7;
00509         RXB0CON            &= ~(1 << RXFUL);            // We ACK the reception, mark the slot as being empty, free for the next packet
00510     
00511         switch (CanMsgR.messageID & 0x000F)             // The command is the last 4 bits of SID
00512         {
00513             case WRITE_FLASH_ADDRESS_COMMAND:           // sets up the address for program memory writting
00514                 write_flash_address();
00515                 acknowledge_packet();
00516                 break;
00517 
00518             case WRITE_FLASH_DATA_COMMAND:              // writes to the program memory
00519                 write_flash_data();
00520                 acknowledge_packet();
00521                 break;
00522     
00523             case READ_FLASH_COMMAND:
00524                 read_flash();                           // special ack, done in the function, will ack with the data
00525                 break;
00526 
00527             case ERASE_FLASH_COMMAND:
00528                 erase_flash();                          // erases program memory
00529                 acknowledge_packet();
00530                 break;
00531 
00532             case RESET_COMMAND:
00533                 write_eeprom();
00534                 acknowledge_packet();
00535                 _asm
00536                     goto 0x0000                         // This jumps to the Reset vector
00537                 _endasm
00538                 // no break needed because of the goto above
00539 
00540             case READ_VERSION_COMMAND:                  // should return the boot loader version number
00541                 CanMsgT.messageID = CanMsgR.messageID | 0x10;
00542                 CanMsgT.d.byte[0] = 0x40;
00543                 CanMsgT.d.byte[1] = 0x41;
00544                 CanMsgT.d.byte[2] = 0x42;
00545                 CanMsgT.d.byte[3] = 0x43;
00546                 CanMsgT.length = 4;
00547                 sendCanMsg();
00548                 break;
00549 
00550             case MAGIC_PACKET:                          // Means "reboot", it will be ACK'ed at boot time (in the main())
00551                 _asm
00552                     goto 0x0000
00553                 _endasm
00554                 // no break needed because of the goto above
00555 
00556             //default:
00557                 // Perhaps we should send back some kind of error packet?       
00558         }
00559     }
00560 
00561 /*
00562     if ( (RXB1CON & (1 << RXFUL) ) )                    // DEBUGGING
00563     {
00564         Nop();
00565     }
00566 */
00567 }
00568 
00569 
00570 
00575 void serious_error(void)
00576 {
00577     while(1)
00578     {
00579     }
00580 }
00581 
00582 
00583 
00587 void send_bootloader_hello_message(void)
00588 {
00589     CanMsgT.length = 8;                     // The following lines craft an ACK for a switch-to-bootloader message
00590 
00591     CanMsgT.d.word[0] = 0xAA55;             // swapped because of endianness
00592     CanMsgT.d.word[1] = 0xAA55;
00593     CanMsgT.d.word[2] = 0xAA55;
00594     CanMsgT.d.word[3] = 0xAA55;
00595     CanMsgT.messageID = motor_id;
00596     CanMsgT.messageID <<= 5;
00597     CanMsgT.messageID  |= 0x600 | 0x0010 | 0x00A;
00598 
00599     sendCanMsg();                           // We ACK the magic packet at boot time
00600 }
00601 
00602 
00603 
00609 void main(void)
00610 {
00611     WDTCON = 0;                             // disables the watchdog
00612                                             // has no effect if the configuration bit WDTEN is enabled
00613 
00614     motor_id = read_eeprom(0x00);
00615 
00616     if (motor_id == 0xFF)
00617         serious_error();
00618 
00619     if ( we_should_boot() )                 // We check if we should directly jump to the user application
00620     {
00621     _asm
00622         goto 0x04c0                         // This jumps to the _entry of user application
00623     _endasm
00624     }
00625 
00626 
00627                                             // From here we are in boot loader mode
00628                                             // ------------------------------------
00629 
00630     position = 0;                           // Resets the position for the "write to flash" process
00631     can_init();                             // Initializes ECAN module
00632     send_bootloader_hello_message();        // Tell the host we have entered bootloader mode, and are ready to program!
00633 
00634 
00635 
00636     while (1)                               // Main loop
00637     {                                       // ---------
00638         handle_can_msg();                   // checks if we have received a CAN msg, and handles it
00639     }
00640 }


sr_external_dependencies
Author(s): Ugo Cupcic/ ugo@shadowrobot.com, software@shadowrobot.com
autogenerated on Thu Jan 2 2014 12:01:42