University Programs Knowledge Base

cancel
Showing results for 
Show  only  | Search instead for 
Did you mean: 

University Programs Knowledge Base

Discussions

Sort by:
Click Here : https://community.freescale.com/servlet/JiveServlet/downloadBody/102170-102-1-18605/OpenSDA.zip To download the file with the files mentioned on the presentation.
View full article
All information can be found in this document
View full article
This tutorial covers the details of Turning A Servo on the Kinetis K40 using TWR-K40x256-KIT evaluation board. Overview In this exercise you will build a “bare metal” (no RTOS) application which turns a servo, targeting a Freescale K40 board. You will: Create the Servo code in CodeWarrior Build the Servo project Download and run the code on a Kinetis K40 Tower System board Learn how to utilize the FlexTimer module to control a Servo   To successfully complete this exercise you need the following board and development environment. The K40 Tower card, TWR-K40x256 Tower Elevator Panels Servo Prototyping Board Power to your servo - either utilize the 7.2v Nicad Battery or a DC power supply CodeWarrior for Microcontrollers 1. Hardware 2. Create a New CodeWarrior Project 3. Build the Code 4. Download/Debug/Run 5. Learning Step: Servo Code Description Example Code Variables Init_PWM_Servo PWM_Servo PWM_Servo_Angle Set Up a Look-Up Table for Servo Angles Other K40 Tutorials: Links 1. Hardware   The first step of this tutorial requires you read the Turn A Servo article for background information on servo's, timer modules, PWM signals and counters. You will need to connect your servo to the microcontroller and also to a separate power source. 2. Create a New CodeWarrior Project The next step is to create a new project (or add this code to an existing project). 3. Build the Code If you have more than one project in your project view, make sure the proper project is the focus. The most reliable way to do this is to right click the project and choose Build Project as shown below. You can also go to the Project menu and choose the same command. If you encounter errors, look in the Problems view and resolve them. You can ignore any warnings. 4. Download/Debug/Run This link shows a video of the servo turning the wheels from left to right in small increments http://www.youtube.com/watch?v=QgwASk9DHvU&feature=relmfu 5. Learning Step: Servo Code Description Your code will sweep your servo from max to minimum angular position, and then back again continuously. Example Code This code sets up the Pulse Width Modulation Timer Module for use by a servo. It is set to utilize Edge-Aligned PWM, and this file properly configures the period, and pulse width for use by the other modules Several important functions are contained in this file: 1. Init_PWM_Servo () - initializes the timer module 2. PWM_Servo (double duty_Cycle) - enter the desired duty cycle setting for the servo 3. PWM_Servo_Angle (int Angle) - enter the desired angle for the servo Straight forward - PWM_Servo_Angle (45) Full left - PWM_Servo_Angle (90)Full right - PWM_Servo_Angle (0)   4. Servo_Tick - interrupt routine which executes once/servo period PWM_Servo (double duty_Cycle) Init_PWM_Servo () PWM_Servo_Angle (float Angle) void ServoTick() Variables FTM0_CLK_PRESCALE TM0_OVERFLOW_FREQUENCY Pulse_Width_Low Pulse_Width_High Total_Count Low_Count Scale_Factor Angle Init_PWM_Servo Void Init_PWM_Servo () { //Enable the Clock to the FTM0 Module SIM_SCGC6 |= SIM_SCGC6_FTM0_MASK;  //Pin control Register (MUX allowing user to route the desired signal to the pin.  PORTC_PCR4  = PORT_PCR_MUX(4)  | PORT_PCR_DSE_MASK; //FTM0_MODE[WPDIS] = 1; //Disable Write Protection - enables changes to QUADEN, DECAPEN, etc.  FTM0_MODE |= FTM_MODE_WPDIS_MASK; //FTMEN is bit 0, need to set to zero so DECAPEN can be set to 0 FTM0_MODE &= ~1; //Set Edge Aligned PWM FTM0_QDCTRL &=~FTM_QDCTRL_QUADEN_MASK;  //QUADEN is Bit 1, Set Quadrature Decoder Mode (QUADEN) Enable to 0,   (disabled) // Also need to setup the FTM0C0SC channel control register FTM0_CNT = 0x0; //FTM Counter Value - reset counter to zero FTM0_MOD = (PERIPHERAL_BUS_CLOCK/(1<<FTM0_CLK_PRESCALE))/FTM0_OVERFLOW_FREQUENCY ;  // Count value of full duty cycle FTM0_CNTIN = 0; //Set the Counter Initial Value to 0 // FTMx_CnSC - contains the channel-interrupt status flag control bits FTM0_C3SC |= FTM_CnSC_ELSB_MASK; //Edge or level select FTM0_C3SC &= ~FTM_CnSC_ELSA_MASK; //Edge or level Select FTM0_C3SC |= FTM_CnSC_MSB_MASK; //Channel Mode select //Edit registers when no clock is fed to timer so the MOD value, gets pushed in immediately FTM0_SC = 0; //Make sure its Off! //FTMx_CnV contains the captured FTM counter value, this value determines the pulse width FTM0_C3V = FTM0_MOD; //Status and Control bits FTM0_SC =  FTM_SC_CLKS(1); // Selects Clock source to be "system clock" or (01) //sets pre-scale value see details below FTM0_SC |= FTM_SC_PS(FTM0_CLK_PRESCALE); /******begin FTM_SC_PS details **************************** * Sets the Prescale value for the Flex Timer Module which divides the * Peripheral bus clock -> 48Mhz by the set amount * Peripheral bus clock set up in clock.h *  * The value of the prescaler is selected by the PS[2:0] bits.  * (FTMx_SC field bits 0-2 are Prescale bits -  set above in FTM_SC Setting) *  *  000 - 0 - No divide *  001 - 1 - Divide by 2 *  010 - 2 - Divide by 4 *  011 - 3 - Divide by 8 *  100 - 4 - Divide by 16 *  101 - 5 - Divide by 32 *  110 - 6 - Divide by 64 - *  111 - 7 - Divide by 128 *  ******end FTM_SC_PS details*****************************/ // Interrupts FTM0_SC |= FTM_SC_TOIE_MASK; //Enable the interrupt mask.  timer overflow interrupt.. enables interrupt signal to come out of the module itself...  (have to enable 2x, one in the peripheral and once in the NVIC enable_irq(62);  // Set NVIC location, but you still have to change/check NVIC file sysinit.c under Project Settings Folder } PWM_Servo Void PWM_Servo (double duty_Cycle) {          FTM0_C3V =  FTM0_MOD*(duty_Cycle*.01); } PWM_Servo_Angle //PWM_Servo_Angle is an integer value between 0 and 90 //where 0 sets servo to full right, 45 sets servo to middle, 90 sets servo to full left void PWM_Servo_Angle (float Angle) {    High_Count = FTM0_MOD*(Pulse_Width_High)*FTM0_OVERFLOW_FREQUENCY;    Low_Count = FTM0_MOD*(Pulse_Width_Low)*FTM0_OVERFLOW_FREQUENCY;    Total_Count = High_Count - Low_Count;    Scale_Factor = High_Count -Total_Count*(Angle/90);     FTM0_C3V = Scale_Factor; //sets count to scaled value based on above calculations } Set Up a Look-Up Table for Servo Angles int main(void) {   //Servo angles can be stored in a look-up table for steering the car.   float table[n] = { steering_angle_0;    steering_angle_1;    steering_angle_2;   ……    steering_angle_n-1    };   Steering_Angle = table[x];   PWM_Servo_Angle (Steering_Angle); // Call PWM_Servo_Angle function. } Other K40 Tutorials: K40 Blink LED Tutorial K40 DC Motor Tutorial Kinetis K40: Turning A Servo K40 Line Scan Camera Tutorial Links Kinetis K40 TWR-K40X256-KIT
View full article
This tutorial will introduce you to I 2 C and provide a framework that you can use to start communicating with various devices that use I 2 C. This tutorial is meant for the Kinetis K40 and will probably not work on any other Kinetis chip. DISCLAIMER: This has not been fully tested and may not work for you and for all devices. The header file provided does not handle errors and should not be used for critical projects. 2C signaling I2C header file Example of I2C communication using Freescale MMA8452Q 3-axis accelerometer Introduction to I 2 C signaling I 2 C is a simple two wire communication system used to connect various devices together, such as Sensory devices and microprocessors using 8 bit packets. I 2 C requires two wires: the first is called SDA and is used for transferring data, the second is called SCL and it is the clock used to drive the data to and from devices. I 2 C uses an open drain design which requires a pull up resistor to logic voltage (1.8,3.3,5) on both SDA and SCL for proper operation. I 2 C is a master-slave system where the master drives the clock and initiates communication. The I 2 C protocol has 5 parts. The Start signal which is defined as pulling the SDA line low followed by pulling SCL low. The slave device address including the Read/Write bit The register address that you will be writing to/ reading from the data The acknowledgement signal which is sent from the receiving device after 8 bits of data has been transferred successfully. the Stop signal, which is defined by SDA going high before SCL goes high. 1. The start signal is sent from the Master to intiate communication on the bus. The start and stop signals are the only time that SDA can change out of sync with SCL. Once the start signal is sent no other device can talk on the bus until the stop signal is sent. If for whatever reason another device tries to talk on the bus then there will be an error and the K40 can detect this. 2. The slave device is a 7 bit (sometimes 10bit but this will not be covered in this tutorial) address provided by the device and is specific to the device. The type of data operation (read/write) is determined by the 8 th bit. A 1 will represent a write and a 0 a read operation. 3. The register addresses are provided by the device's specifications. 4. The data you will send to a device if you are writing or the data that you receive from the device when reading. This will always be 8 bits. 5. After 8 bits of data has been transferred successfully the receiving device will pull the SDA line low to signify that it received the data. If the transmitting device does not detect an acknowledgement then there will be an error. The K40 will be able to detect this. 6. The stop signal is sent from the Master to terminate communication on the bus. Some devices require this signal to operate properly but it is required if there will be more than one master on the bus (which will not be covered in this tutorial) I2C header file This header file only has functions for reading and writing one byte at a time. Most devices support reading and writing more than one byte at a time without sending the Stop signal. Typically the device will keep incrementing the register's address to the next one during read/writes when there is no stop signal present. See your device's user manual for more information. /* * i2c.h * * Created on: Apr 5, 2012 * Author: Ian Kellogg  * Credits: Freescale for K40-I2C example */  #ifndef I2C_H_  #define I2C_H_  #include "derivative.h"  #define i2c_EnableAck() I2C1_C1 &= ~I2C_C1_TXAK_MASK #define i2c_DisableAck() I2C1_C1 |= I2C_C1_TXAK_MASK  #define i2c_RepeatedStart() I2C1_C1 |= I2C_C1_RSTA_MASK  #define i2c_Start() I2C1_C1 |= I2C_C1_TX_MASK;\    I2C1_C1 |= I2C_C1_MST_MASK  #define i2c_Stop() I2C1_C1 &= ~I2C_C1_MST_MASK;\    I2C1_C1 &= ~I2C_C1_TX_MASK  #define i2c_EnterRxMode() I2C1_C1 &= ~I2C_C1_TX_MASK;\    I2C1_C1 |= I2C_C1_TXAK_MASK  #define i2c_write_byte(data) I2C1_D = data  #define i2c_read_byte() I2C1_D  #define MWSR 0x00 /* Master write */  #define MRSW 0x01 /* Master read */  /* * Name: init_I2C * Requires: nothing * Returns: nothing * Description: Initalizes I2C and Port E for I2C1 as well as sets the I2C bus clock */  void init_I2C()  {    SIM_SCGC4 |= SIM_SCGC4_I2C1_MASK; //Turn on clock to I2C1 module    SIM_SCGC5 |= SIM_SCGC5_PORTE_MASK; // turn on Port E which is used for I2C1    /* Configure GPIO for I2C1 function */    PORTE_PCR1 = PORT_PCR_MUX(6) | PORT_PCR_DSE_MASK;    PORTE_PCR0 = PORT_PCR_MUX(6) | PORT_PCR_DSE_MASK;    I2C1_F = 0xEF; /* set MULT and ICR This is roughly 10khz See manual for different settings*/    I2C1_C1 |= I2C_C1_IICEN_MASK; /* enable interrupt for timing signals*/  }  /* * Name: i2c_Wait * Requires: nothing * Returns: boolean, 1 if acknowledgement was received and 0 elsewise  * Description: waits until 8 bits of data has been transmitted or recieved */  short i2c_Wait() {    while((I2C1_S & I2C_S_IICIF_MASK)==0) {    }     // Clear the interrupt flag    I2C1_S |= I2C_S_IICIF_MASK;  }  /* * Name: I2C_WriteRegister * Requires: Device Address, Device Register address, Data for register * Returns: nothing * Description: Writes the data to the device's register */  void I2C_WriteRegister (unsigned char u8Address, unsigned char u8Register, unsigned char u8Data) {    /* shift ID in right position */    u8Address = (u8Address << 1)| MWSR;    /* send start signal */    i2c_Start();    /* send ID with W/R bit */    i2c_write_byte(u8Address);    i2c_Wait();    // write the register address    i2c_write_byte(u8Register);    i2c_Wait();    // write the data to the register    i2c_write_byte(u8Data);    i2c_Wait();    i2c_Stop();  }  /* * Name: I2C_ReadRegister_uc * Requires: Device Address, Device Register address * Returns: unsigned char 8 bit data received from device * Description: Reads 8 bits of data from device register and returns it */  unsigned char I2C_ReadRegister_uc (unsigned char u8Address, unsigned char u8Register ){    unsigned char u8Data;    unsigned char u8AddressW, u8AddressR;    /* shift ID in right possition */    u8AddressW = (u8Address << 1) | MWSR; // Write Address    u8AddressR = (u8Address << 1) | MRSW; // Read Address    /* send start signal */    i2c_Start();    /* send ID with Write bit */    i2c_write_byte(u8AddressW);    i2c_Wait();    // send Register address    i2c_write_byte(u8Register);    i2c_Wait();    // send repeated start to switch to read mode    i2c_RepeatedStart();    // re send device address with read bit    i2c_write_byte(u8AddressR);    i2c_Wait();    // set K40 in read mode    i2c_EnterRxMode();    u8Data = i2c_read_byte();    // send stop signal so we only read 8 bits    i2c_Stop();    return u8Data;  }  /* * Name: I2C_ReadRegister * Requires: Device Address, Device Register address, Pointer for returned data * Returns: nothing * Description: Reads device register and puts it in pointer's variable */  void I2C_ReadRegister (unsigned char u8Address, unsigned char u8Register, unsigned char *u8Data ){    /* shift ID in right possition */    u8Address = (u8Address << 1) | MWSR; // write address    u8Address = (u8Address << 1) | MRSW; // read address    /* send start signal */    i2c_Start();    /* send ID with W bit */    i2c_write_byte(u8Address);    i2c_Wait();    // send device register    i2c_write_byte(u8Register);    i2c_Wait();    // repeated start for read mode    i2c_RepeatedStart();    // resend device address for reading    i2c_write_byte(u8Address);    i2c_Wait();    // put K40 in read mode    i2c_EnterRxMode();    // clear data register for reading    *u8Data = i2c_read_byte();    i2c_Wait();    // send stop signal so we only read 8 bits    i2c_Stop();    }  #endif  Example of I2C communication using Freescale MMA8452Q 3-axis accelerometer This example is very simplistic and will do nothing more than read the WHO AM I register to make sure that I 2 C is working correctly. To see more check out the Freescale MMA8452Q Example /* Main. C */ #include <stdio.h> #include "derivative.h" /* include peripheral declarations */ #include "i2c.h" int main(void) {      // checking the WHO AM I register is a great way to test if communication is working      // The MMA8452Q has a selectable address which is either 0X1D or 0X1C depending on the SA0 pin      // For the MMA8452Q The WHO AM I register should always return 0X2A      if (I2C_ReadRegister_uc (0x1D,0x0D) != 0x2A {           printf ("Device was not found\n");      } else {           printf ("Device was found! \n");      } }
View full article
This tutorial is meant to introduce you to the use of a push button. It will give an explanation and example code of how you could implement a push button. Push buttons can be a great way to set a number of different states. Push buttons are advantageous because you can change your code physically versus pulling up the debugger every time you want to make a little change. ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ Usage A button can have many different functions on your autonomous vehicle. Most notably the button has been used for testing to start, stop, or put your car in a configuration mode. Configuration mode would let you test to see if all the peripherals except the motors are working. This would help you test your camera data and servo angles without always having to run after your car. During your race you can even set your button to different speed states. Since you have two chance to traverse the track you may have a slower safer speed on one state and a faster speed the pushes the limit on another state. In the end, what you do with the button is up to you and the choices are unlimited. Description of Example Code Below there will be an example of how to implement a push button. This push button will be connected to PTA16. When reading this pin a high, "1" or 5V, is considered "OFF" and a low, "0" or 0V, is considered "ON." To reduce the effects of bounce and/or the chance of a false press, additional code has been added to filter the signal. This is done by checking the button every 10ms for 50ms. If the button has been pressed for 3 or more of the 5 times we will change the state, otherwise it will not be considered a "press." Button Initialization Here is the initialization code that can be put in a header such as "Button.h." #define BUTTONLENGTH 5   // Button's Defined State   // 0 means button not pressed   // 1 means button pressed short fButton = 0; short iButtonCount=0; short iButtonTimer=0;   // Button Triggered Start time short iButtonTime; void initButton() {   //turn on clock to Port A   SIM_SCGC5 |= SIM_SCGC5_PORTA_MASK;   // configure pin to be GPIO   PORTA_PCR16 = PORT_PCR_MUX(1) | PORT_PCR_DSE_MASK;   // configure PTA16 to be input   GPIOA_PDDR &= (0<<16);  } See GPIO for explanation of how these specific commands work. Button Implementation Below is an example of a function that implements the button function. This function can be stored in a header file "Button.h" along with the initialization code. To call this function you would just place "readButton();" in your 10ms Flextimer source code. Read comments for description of each line Void readButton () {                  short fButtonState  = 0;   // initializes the button state to "OFF"           iButtonCount++;            // increments button count      if (GPIOA_PDIR & (1<<16)) {                    // if button read as high then its off otherwise its on           fButtonState = 0;      } else {           fButtonState = 1;      }      if (fButtonState && ! fButton) {                          // if the button is pushed and it previously wasn't then start a count           iButtonTimer++;           if (iButtonTimer <= 1) {                                                             iButtonCount = 0;                                 // Reset the Button Count if the timer is less or equal to 1           }      } else if (! fButtonState && fButton) {           iButtonTimer++;           if ( iButtonTimer <= 1) {                iButtonCount = 0;                               // Reset the Button count if the timer is less or equal to 1           }      }      if ( iButtonCount > BUTTONLENGTH && iButtonTimer >0) {     // if button has been read for 50ms check to see if we passed the test!           if ( iButtonTimer > (3*BUTTONLENGTH/4) && fButton) {                // fButton = 0;           } else if (iButtonTimer > (3*BUTTONLENGTH/4) && ! fButton) {                fButton = 1;           }           iButtonCount = 0;           iButtonTimer = 0;     } }
View full article
This tutorial covers the specific details of obtaining data from the line scan camera on the Qorivva TRK-MPC5604B board. This tutorial will help students familiarize themselves with how to interface the camera with the microcontroller, how to configure GPIO pins to create clock signals and also how to utilize the microcontroller's ADC to read the data from the camera. Outside of control algorithms, configuring the camera is one of the more complex tasks necessary to create a Freescale Cup Vehicle. 1. Overview 2. Hardware 3. Set up the Hardware: Line Scan Camera/Microcontroller Hardware Setup 4. Build the Code 5. Download/Debug/Run 6. Learning Step Functions Calling the Function Variables Setting threshold. (This can give you a simple view of what your camera sees without connecting it to a scope) Sample Code Download Link Alternative Examples Other Qorivva Tutorials: Links External 1. Overview In this exercise students will access the line scan camera, create a clock signal and create the initialization pulse which tells the camera to begin the exposure period. This tutorial will not describe line recognition or line following algorithms - these concepts are beyond its scope. Students will: Open the example file using Codewarrior Build a project Download the code to the board connect the microcontroller to the camera via the motor control board Run the program view the camera data, clock and Si pulse on an oscilloscope To successfully complete this exercise, students will need the following board and development environment: TRK-MPC5604B Motor Drive Board Version A Freescale Cup TRK-MPC5604B compatible Car Kit CodeWarrior for Microcontrollers v 2.8 P&E Micro Toolkit Freescale Line Scan Camera USB Cord Knowledge of how Pointers and arrays are utilized in C 2. Hardware   Read the Obtain Data From Line Scan Camera overview article for general information on the camera, ADC, and GPIO microcontroller configuration settings. Connect the sensors, motor drive board and microcontroller of your car according to the TRK-MPC5604B chassis build instructions 3. Set up the Hardware: Line Scan Camera/Microcontroller Hardware Setup It is crucial for an engineer to have the proper test equipment and tools for the job. In this case, without an oscilloscope, students will not be able to verify whether the proper signals are being sent to the camera, or that the camera is working properly. 4. Build the Code If there is more than one project in your project view, make sure the proper project is the focus. The most reliable way to do this is to right click the project and choose Build Project as shown below. You can also go to the Project menu and choose the same command. If errors are encountered, look in the Problems view and resolve them. For now ignore any warnings. 5. Download/Debug/Run Download the code to your board, once this process is complete resume the project so that the code runs. 6. Learning Step What will happen: the function ImageCapture() is called in main.c with a pointer to the first element in the array. This function completes the processes necessary to capture images using the camera. To become more familiar with Pointers and Arrays - navigate to the C Programming Tutorial. Knowledge of Pointers and Arrays is a pre-requisite for understanding the Camera Code. Functions void CAMERA(void) {   TransmitData("****Line Sensor Test****\n\r");   SIU.PCR[27].R = 0x0200; /* Program the Sensor read start pin as output*/   SIU.PCR[29].R = 0x0200; /* Program the Sensor Clock pin as output*/   for(j=0;j<2;j++)   //for(;;)   {   SIU.PCR[27].R = 0x0200; /* Program the Sensor read start pin as output*/   SIU.PCR[29].R = 0x0200; /* Program the Sensor Clock pin as output*/   SIU.PGPDO[0].R &= ~0x00000014; /* All port line low */   SIU.PGPDO[0].R |= 0x00000010; /* Sensor read start High */   Delay();   SIU.PGPDO[0].R |= 0x00000004; /* Sensor Clock High */   Delay();   SIU.PGPDO[0].R &= ~0x00000010; /* Sensor read start Low */   Delay();   SIU.PGPDO[0].R &= ~0x00000004; /* Sensor Clock Low */   Delay();   for (i=0;i<128;i++)   {   Delay();   SIU.PGPDO[0].R |= 0x00000004; /* Sensor Clock High */   ADC.MCR.B.NSTART=1; /* Trigger normal conversions for ADC0 */   while (ADC.MCR.B.NSTART == 1) {};   adcdata = ADC.CDR[0].B.CDATA;   Delay();   SIU.PGPDO[0].R &= ~0x00000004; /* Sensor Clock Low */   Result[i] = (uint8_t)(adcdata >> 2);    }   Delaycamera();   //printlistall();   }   printlistall(); } Calling the Function within the main for loop in main.c, call the camera function using the following code: for (;;)   {   CAMERA();   } Variables Creates an 128x1 array for camera data information volatile uint8_t Result[128]; /* Read converstion result from ADC input ANS0 */   Setting threshold. (This can give you a simple view of what your camera sees without connecting it to a scope) #define THRESHOLD (2.0 /*volts*/ / 0.03125) // 8-bit A/D = 31.25mV/bit CAMERA(); // read line sensor, 128x1 pixel result returned in Result[128] array // print result for (i = 16; i < 112; ++i) // ignore the first and last 16 bits in the camera frame   if (Result[i] < THRESHOLD)   TransmitCharacter('1'); // black (low intensity)   else   TransmitCharacter('0'); // white (high intensity) Sample Code Download Link Qorivva Sample Code Download Link Alternative Examples Application Note 4244 and Software. Other Qorivva Tutorials: 1. Qorivva: Blink LED 2. Qorivva: Drive DC Motor Tutorial 3. Qorivva: Turning A Servo 4. Qorivva: Line Scan Camera Tutorial Links Qorivva Overview https://community.nxp.com/docs/DOC-1019 External TRK-MPC5064B Freescale Webpage TRK-MPC5064B Freescale Reference Manual TRK-MPC5064B Freescale Schematic
View full article
Project Summary Skills Developed: Materials: Step 0: Prerequisite Videos Step 1: Get a FRDM-JAM Step 2: Put it Together Step 3: Download Step 4: Hack and Slash! Sound Samples Utilities, etc: Project Summary MonkeyJam will use the FRDM-K20D50 board (which has a Cortex M4 core with DSP instructions) along with the FRDM-JAM shield so you can  make your very own guitar /bass  stomp box.  The end result will be a functional DSP system that will allow you to do high quality amplifier simulation and effects. The FRDM-JAM does not limit you to DSP on musical instruments!  There are 3.5mm stereo jacks to DSP filtering any type of audio signal.    You could even use the USB interface to create a USB-MIDI Synthesizer!  Lastly,  no need to bring the house down.....  a headphone amplifier circuit is provided so you can jam out without bothering the neighbors. MBED Support coming *very soon* Skills Developed: Real Time Processing DSP Algorithms Fixed Point Mathematics 24-bit I2S Data Converter Interfacing Soldering SOIC8 and 1206 Surface mount devices Cortex CMSIS DSP Library Materials: FRDM-K20D50 FRDM-JAM Development Tools Install Codewarrior 10.5 for Microcontrollers (Eclipse) Special Edition to your  machine Example Code Get the latest copy from Github Step 0: Prerequisite Videos The videos are organized into a nice YouTube playlist: H.I.T 1: Monkey Jam - YouTube https://www.youtube.com/playlist?list=PLWM8NW5LEukgM-D5eRMtKZ8R2WfXnqKGp MonkeyJam Watch Me 1st FRDM-JAM Hardware Overview MonkeyJam Software Overview Introduction to Fixed Point Math for Embedded Systems - Part 1 of 3 Introduction to Fixed Point Math for Embedded Systems - Part 2 of 3 Introduction to Fixed Point Math for Embedded Systems - Part 3 of 3 Real Time Signal Processing Part 1 of 3 Real Time Signal Processing Part 2 of 3 Real Time Signal Processing Part 3 of 3 q31_t (Q0.31) Number Format for the CMSIS DSP Libraries and the MonkeyJam Software Guitar physics in a nutshell Ideas for hacking the MonkeyJam Step 1: Get a FRDM-JAM MonkeyJam Build Package on the FRDM-JAM site.    Please let us know if you are interested in a pre-assembled version.  If there is enough demand we will get some preassembled for purchase, I will get a Kickstarter going!   Don't be afraid to build it yourself,  Soldering is fun!  There is plenty of good stuff on the web on how to do SMT soldering.  All of the parts on the board are fairly simply once you get the hang of it and everything can be hand soldered  The key is having some decent tools. Step 2: Put it Together Attach the FRDM-JAM to the FRDM-K20D50.  The FRDM-K20D50 comes with female headers that you can solder on so the boards can be easily separated.  Note that as of Rev Gamma (current version),   it is possible to connect to a K64F.    The software isn't quite there but it hardware connections are available.   If you are unsure,  stick with the FRDM-K20D50 Step 3: Download Download the Example Software from Github.  The video "Loading and Configuring the MonkeyJam Example Software" will step you though downloading the program and doing some basic configuration. Step 4: Hack and Slash! Plug In and jam! Sound Samples Each sound sample was my Carvin Ultra-V guitar plugged direct into the MonkeyJam Board.  The output was fed to a Zoom Handy Recorder H4n (Thanks to Brandin Claar of Remodulate LLC for the recorder).  The H4N recorded the signal at 44.1KHz Sample rate @16-bit.  The sound files were converted to mono format via Goldwave.  No processing (other than a  volume boost on the files) was performed.   I listen to the recording in real-time via a line out on the H4N.  File (See Attachments) Patch Notes STE-003-Neck-a12b12g12-mlike.wav PATCH_TUBEY_CLEAN Neck Pickup Alpha Pot - 12 O'Cock Beta Pot - 12 O'Cock Gamma Pot - 12 O'Cock Pattern Similar to Metallica Sanitarium STE-005-Neck-a7b5g5-mlike.wav PATCH_TUBEY_CLEAN Neck Pickup Alpha Pot - 7 O'Cock Beta Pot - 5 O'Cock Gamma Pot - 5 O'Cock Pattern Similar to Metallica Sanitarium STE-006-Neck-a12b7g5-mlike.wav PATCH_TUBEY_CLEAN Neck Pickup Alpha Pot - 12 O'Cock Beta Pot - 7 O'Cock Gamma Pot - 5 O'Cock Pattern Similar to Metallica Sanitarium STE-007-Neck-VariousSettings-d-g-em_strum.wav PATCH_TUBEY_CLEAN Neck Pickup The pots were moved around throughout the file Strummed D-Major, G-Major and E-Minor STE-008-Neck+Bridge-VariousSettings-d-g-em_strum.wav PATCH_TUBEY_CLEAN Neck + Bridge Pickup The pots were moved around throughout the file Strummed D-Major, G-Major and E-Minor STE-009-Bridge-VariousSettings-d-g-em_strum.wav PATCH_TUBEY_CLEAN Bridge + Bridge Pickup The pots were moved around throughout the file Strummed D-Major, G-Major and E-Minor STE-010-Neck-VariousSettings-Jammy.wav PATCH_TUBEY_CLEAN Neck + Bridge Pickup The pots were moved around throughout the file B-Minor Type Jam STE-011- Bridge - Various Settings - On-Off Demo-RandomDroppedD.wav PATCH_OVERDRIVE Bridge Pickup Alpha Pot - 5 O'Cock Beta Pot - 12 O'Cock Gamma Pot - 12 O'Cock Random Dropped D twiddling STE-012- Neck - Various Settings - On-Off Demo-Jammy.wav PATCH_OVERDRIVE Neck Pickup Alpha Pot - 5 O'Cock Beta Pot - 7 O'Cock Gamma Pot - 7 O'Cock Random B-Minor twiddles (bluesy) PATCH_OVERDRIVE             +––––––––––––––––––+      +––––––––––––––––––––––––––+      +–––––––––––––––––––––+                               |                  |      |                          |      |                     |                    Signal In  |    IIR BiQuad    |      |      Hard Overdrive      |      |      IIR BiQuad     |  Signal Out       +–––––––––+>|                  +––––+>|                          +––––+>|                     +–––––––––––––+>                |   [Peaking EQ]   |      | [atan24pi Look Up Table] |      |  [Low Pass Filter]  |                               |                  |      |                          |      |                     |                               +––––––––––––––––––+      +––––––––––––––––––––––––––+      +–––––––––––––––––––––+                                                                                                                                                     0.1 < Q < 1.5    [Pot Alpha]                                     Q = 0                                                                                                                                                              50 < Fs < 750    [Pot Gamma]                                   Fs = 2000                                                                                                                                                          -20 < dbGain < 20  [Pot Beta]                                                                                                                                                                                        PATCH_TUBEY_CLEAN              +––––––––––––––––––+      +––––––––––––––––––––––––––+      +–––––––––––––––––––––+                               |                  |      |                          |      |                     |                    Signal In  |    IIR BiQuad    |      |      Soft Overdrive      |      |      IIR BiQuad     |  Signal Out       +–––––––––+>|                  +––––+>|                          +––––+>|                     +–––––––––––––+>                |     [LowShelf]   |      | [atan4pi Look Up Table]  |      |  [Low Pass Filter]  |                               |                  |      |                          |      |                     |                               +––––––––––––––––––+      +––––––––––––––––––––––––––+      +–––––––––––––––––––––+                                                                                                                                                     0.05 < Q < 2.58   [Pot Alpha]                                     Q = 2.0                                                                                                                                                             1000 < Fs < 4000    [Pot Beta]                                   Fs = 2500                                                                                                                                                      -15 < dbGain < 15  [Pot Gamma]                                                                                                                                                                                    Utilities, etc: Biquad Filter View - A IIR Biquad Filter Design &amp; Visualization Tool
View full article
This tutorial covers the details of Driving a motor on the Qorivva TRK-MPC5604B: MPC5604B StarterTRAK evaluation board. Overview 1. Put together the Car Chassis: Motor Controller Board Version A. 2. Import the Sample Project 3. Build the Code 4. Download/Debug/Run 5. Learning Step: DC Motor Code Description Functions Motor_Right () & Motor_Left() Motor_Right_Current () & Motor_Left_Current() Sample Code Download Link Alternative Examples: Other Qorivva Tutorials: Useful Technical Links Overview In this exercise students will utilize the sample project to turn a DC motor on an off using the Qorivva TRK-MPC5604B board. Students will: Put together the car chassis Open the Sample Project Make changes to main.c to call the motor functions Build the Motor function code Download and run the code on a Qorivva TRK-MPC5604B board. Learn how the code works To successfully complete this exercise students will need the following board and development environment. Qorivva TRK-MPC5604B board. Freescale Cup Chassis (connector for the motor/board) Motor Drive Version A board Kit Cables and interconnects 7.2v Nicad Battery CodeWarrior for Microcontrollers V2.8 Recommend completing the the Blink LED Tutorial Motor Example code 1. Put together the Car Chassis:   There are several steps in this process: Build the Freescale Cup Car Chassis Add the Qorivva-Mpc560xb version components to the chassis The first step of this tutorial is to gain background information on background information on motors, timer modules, PWM signals and counters. To learn more about these general topics read the Drive A DC Motor overview article. You will need to connect your motor to the microcontroller via the Motor Drive board. This board is connected to the battery, and serves to power the motors. separate power source. This is an easy process using the provided Motor Controller Board. Motor Controller Board Version A. The Freescale Cup Motor Drive VA board uses the following connector type: white 3 pin connectors (for motor) (Molex 3-pin .100") white 2 pin connector (for battery) (Molex 2-pin .100") Schematics Wiring Connections for the TRK-MPC5604B 2. Import the Sample Project The next step is to import an existing project into your Workspace. in this case, the TRK-MPC5604B Sample project. Follow the instructions on the codewarrior project import page if you can't remember how to to import the project into CodeWarrior. 3. Build the Code If you have more than one project in your project view, make sure the proper project is the focus. The most reliable way to do this is to right click the project and choose Build Project as shown below. You can also go to the Project menu and choose the same command. If you encounter errors, look in the Problems view and resolve them. You can ignore any warnings. 4. Download/Debug/Run 5. Learning Step: DC Motor Code Description What will happen: This demo is setup for two motors (one left and one right). You will then independently turn on and off each motor Functions This file sets up the Pulse Width Modulation Timer Module for use by a DC Motor. It is set to utilize Edge-Aligned PWM, and this file properly configures the period, and pulse width for use by the other modules Motor_Right () & Motor_Left() void MOTOR_LEFT(void) {   TransmitData("****Left Drive Motor Test****\n\r");   SIU.PCR[16].R = 0x0200; /* Program the drive enable pin of Left Motor as output*/   SIU.PGPDO[0].R = 0x00008000; /* Enable Left the motors */   Delaywait();   SIU.PGPDO[0].R = 0x00000000; /* Disable Left the motors */ } void MOTOR_RIGHT(void) {   TransmitData("****Right Drive Motor Test****\n\r");   SIU.PCR[17].R = 0x0200; /* Program the drive enable pin of Right Motor as output*/   SIU.PGPDO[0].R = 0x00004000; /* Enable Right the motors */   Delaywait();   SIU.PGPDO[0].R = 0x00000000; /* Disable Right the motors */ } Motor_Right_Current () & Motor_Left_Current() void RIGHT_MOTOR_CURRENT(void) {   TransmitData("****Right Motor Current****\n\r");   SIU.PGPDO[0].R = 0x00004000; /* Enable Right the motors */   Delaywait();   for (i=0;i <10;i++)   {   ADC.MCR.B.NSTART=1; /* Trigger normal conversions for ADC0 */   while (ADC.MSR.B.NSTART == 1) {};   curdata = ADC.CDR[2].B.CDATA;   printserialsingned(curdata);    }   SIU.PGPDO[0].R = 0x00000000; /* Disable Right the motors */ } void LEFT_MOTOR_CURRENT(void) {   TransmitData("****Left Motor Current****\n\r");   SIU.PGPDO[0].R = 0x00008000; /* Enable Right the motors */   Delaywait();   for (i=0;i <10;i++)   {   ADC.MCR.B.NSTART=1; /* Trigger normal conversions for ADC0 */   while (ADC.MSR.B.NSTART == 1) {};   curdata = ADC.CDR[1].B.CDATA;   printserialsingned(curdata);    }   SIU.PGPDO[0].R = 0x00000000; /* Disable Right the motors */ } Sample Code Download Link Qorivva Sample Code Download Link Alternative Examples: Application Note 4251 and Software. Other Qorivva Tutorials: Qorivva: Blink a Led Tutorial Qorivva: Turning a Servo Tutorial Qorivva: Line Scan Camera Tutorial Useful Technical Links TRK-MPC5064B Freescale Webpage TRK-MPC5064B Freescale Reference Manual TRK-MPC5064B Freescale Schematic
View full article
This tutorial covers the details of Blinking an LED on the TRK-MPC5604B: MPC5604B StarterTRAK evaluation board. It will introduce the evaluation board, and some basic CodeWarrior features. Overview Hardware Set up the Software Development Environment A. Download and Install Codewarrior B. Download and Install Drivers Sample Code Serial Debugging: I made the hardware modifications for serial debugging: I did not make the hardware modifications for serial debugging: Download/Debug/Run Learning Step: LED Code Description Functions Blink the LED(s): Other Qorivva Tutorials Useful Links to Technical Data Overview In this exercise students will run sample code and build an application which enables testing of the Qorivva TRK-MPC5604B board. Students will: Configure the Software Development Environment Configure the evaluation board hardware Learn how to open CodeWarrior project example files Build a project Download and run the code on TRK-MPC5604B board Learn how to utilize the GPIO Peripheral to blink a LED   To successfully complete this exercise, students will need the following board and development environment. TRK-MPC5604B evaluation board CWX-MPC-5500P-EX: Evaluation: CodeWarrior for MPC55xx/MPC56xx Microcontrollers V2.8 (Classic) RAppID initialization Tool P&E Micro Driver Software Hardware Read the MCU 101: LEDs article for general information on LED circuits. The LED's are located on the board and visible in the board schematic on page 4 as below: This schematic is found here. Set up the Software Development Environment There are several steps necessary to prepare the evaluation board and PC for microcontroller programming and development. Interfacing the evaluation board with a PC requires downloading and installing the CodeWarrior IDE, as well as the device drivers for programming the microcontroller via USB. A. Download and Install Codewarrior Before completing this example project, download and install CodeWarrior for MPC56xx 2.8 or the latest version. B. Download and Install Drivers In addition to CodeWarrior, it may (needs verified) be necessary to install one or both of the following tools: RAppID initialization tool- RAppID comes on the DVD provided with your evaluation board. In the main directory of the DVD, click on the "TRK_MPC5604B.html" file to open the DVD interface which provides user manuals, software, schematics and documentation for the evaluation board. P&E Microcomputer Systems, Inc drivers- P&E is a a computer driver for the TRK-MPC5604B device, enabling evaluation board programming via USB through the CodeWarrior debug OSJTAG interface. This driver can be downloaded here Because this isn't found on the disk. Sample Code To use the Hyperterminal communications features described in the following sections and in the attached sample code you must populate the U5 on your TRK-MPC5604B board. Qorivva Sample Code Download Serial Debugging: To use hyperterminal style debugging through the Serial port you must populate U5 with a RS232 transceiver and C55. I made the hardware modifications for serial debugging: From the Start menu Run the hyper terminal by using All programs> Accessories> Communications> HyperTerminal and make COMx properties port s ettings as Baud rate 115200, Data bits 8, Parity None, Stop bits 1 and Flow control None. 8. In the project menu select make (or F7) you will get few warning messages. I did not make the hardware modifications for serial debugging: In the project menu select MAKE (or F7) you will get few warning messages and can ignore them. Next select Debug option (or F5) from project menu. The debug window opens with few sub windows such as Code, Status and CPU etc. To run the program, select the Source GO menu button. Note: Much of the code in the sample file is utilized to send and receive messages serially. Some quick, minor changes can be applied as follows: Open main.c within the for loop, remove or comment out all the code. Now, manually call the specific function desired, in this case: for (; ; )      {           LED();      } Download/Debug/Run In sample.mcp project manager window target selection window is set to the default RAM. This means the code runs in the RAM. This target option can be changed using the drop down menu to internal_FLASH. This means the code runs in the flash and this code can run without debugger when the board is powered up. You can select either RAM target or internal_FLASH target for the following test procedure. If you select internal_FLASH target you can test the standalone operation of the board. If you encounter errors, look in the Problems view and resolve them. You can ignore any warnings. If the project builds correctly, it is time to download to the board and watch it work. Ensure that the USB cable that came with the board connects the board to the host computer’s USB port. There are multiple ways to issue the Debug command. Right click the project in the projects view and choose Debug As->CodeWarrior Download. Alternatively, y go to the Run menu and choose Debug (F11). Learning Step: LED Code Description Within the sample code, there is a for loop which calls a switch statement. With working hyper-terminal and proper serial connector interface into a PC, entering the numerical characters "1" - "9" into the hyper-terminal will call each separate function initiating the following actions Blinks Leds & outputs text strings to hyperterminal Calls the Switch function - which sends text strings to hyperterminal indicating which switch has been pressed Calls the Servo function which sweeps the servo back and forth; sends text strings to hyperterminal Calls the motor function which enables and disables the left motor; sends status text strings to hyperterminal Calls the motor function which enables and disables the right motor; sends status text strings to hyperterminal Calls the Camera function which sends the correct signals to the camera and reads the data; sends status text strings to hyperterminal Calls the Left_Motor_Current function; sends status text strings to hyperterminal Calls the Right_Motor_Current function; sends status text strings to hyperterminal   (hyperterminal code documentation needs verified ) TransmitData("\n\r**The Freescale Cup**");         TransmitData("\n\r*********************");         TransmitData("\n\r1.Led\n\r");         TransmitData("2.Switch\n\r");         TransmitData("3.Servo\n\r");         TransmitData("4.Motor Left\n\r");         TransmitData("5.Motor Right\n\r");         TransmitData("6.Camera\n\r");         TransmitData("7.Left Motor Current\n\r");         TransmitData("8.Right Motor Current");         TransmitData("\n\r**********************"); option = ReadData(); option = 1;     switch(option)         {             case '1':                 LED();             break;             case '2':                 SWITCH();             break;             case '3':                 SERVO();             break;             case '4':                 MOTOR_LEFT();             break;             case '5':                 MOTOR_RIGHT();             break;             case '6':                 CAMERA();             break;             case '7':                 LEFT_MOTOR_CURRENT();             break;             case '8':                 RIGHT_MOTOR_CURRENT();             break;             default:             break;          } As visible from the schematic - the LED's are accessed via the following ports. Hardware Chip Port/Pin Comment LED1 PE4 LED2 PE5 LED3 PE6 LED4 PE7 Functions The following function is utilized in the code to blink the LED's This function is located in main.c void LED(void) {    SIU.PCR[68].R = 0x0200;  /* Program the drive enable pin of LED1 (PE4) as output*/    SIU.PCR[69].R = 0x0200;  /* Program the drive enable pin of LED2 (PE5) as output*/    SIU.PCR[70].R = 0x0200;  /* Program the drive enable pin of LED3 (PE6) as output*/    SIU.PCR[71].R = 0x0200;  /* Program the drive enable pin of LED4 (PE7) as output*/    TransmitData("****Led Test****\n\r");    TransmitData("All Led ON\n\r");    Delayled();    SIU.PGPDO[2].R |= 0x0f000000;  /* Disable LEDs*/    SIU.PGPDO[2].R &= 0x07000000;  /* Enable LED1*/    TransmitData("Led 1 ON\n\r");    Delayled();    SIU.PGPDO[2].R |= 0x08000000;  /* Disable LED1*/    SIU.PGPDO[2].R &= 0x0b000000;  /* Enable LED2*/    TransmitData("Led 2 ON\n\r");    Delayled();    SIU.PGPDO[2].R |= 0x04000000;  /* Disable LED2*/    SIU.PGPDO[2].R &= 0x0d000000;  /* Enable LED3*/    TransmitData("Led 3 ON\n\r");    Delayled();    SIU.PGPDO[2].R |= 0x02000000;  /* Disable LED3*/    SIU.PGPDO[2].R &= 0x0e000000;  /* Enable LED4*/    TransmitData("Led 4 ON\n\r");    Delayled();    SIU.PGPDO[2].R |= 0x01000000;  /* Disable LED4*/ } Code Details: SIU - System Integration Unit PCR - Port Configuration Register PGPDO - Parallel GPIO Pad Data Output Registers : definition From viewing the user manual, under Functional port pin descriptions, it is Blink the LED(s): Within the main find the infinite for loop. for ( ; ; )      {      } loop of Main.c, remove all code, and add the LED's with the following function: for(;;) { LED(); } To alter the behavior of the LEDs, change the function itself, or pull specific code from the function and insert it within loops of a program for testing purposes. LED's are often used for testing important parts of an algorithm. By connecting an oscilloscope to a LED, it is possible to test the duration of a key algorithm, or to verify if signal timing is as expected along with the visual cue. Other Qorivva Tutorials Qorivva: Drive DC Motor Tutorial Qorivva: Turning A Servo Qorivva: Line Scan Camera Tutorial Useful Links to Technical Data TRK-MPC5064B Freescale Webpage TRK-MPC5064B Freescale Reference Manual TRK-MPC5064B Freescale Schematic
View full article
Take some time to get yourself familiar with C programming before you continue on the programming tutorial. Here is a list of topics that you should be comfortable with, and a couple of good tutorials below. Topics included: Program Structure Commenting Variables Keywords Data Types Decimal, Binary and Hexadecimal Equivalents ASCII Text/Number Conversion Math Operators Increment & Decrement Shift Logical Operators Bitwise Operators Loops If Statement Switch Statement Functions Recursion Local Variables vs. Global Arrays Pointers Typdef, struct and union Preprocessor Directives Static, const and Volatile Keywords Tutorial 1: PSU Intro to C for Embedded Design   From PSU Freescale Cup Senior Design Course Tutorial 2: Learning Programming with C This Freescale course consists of a collection of lessons that will introduce you to the fundamentals of programming using the C programming language. Coding for Readability Sometimes when a project has the ability to grow with new features, it is best to code in modules. This allows one to easily take a more modular approach to designing their program. Despite the fact that C does not support Classes like C++ does, you can create structures that can be addressed globally with little code, which is especially useful for microcontroller based projects. An example of a structure which will be made global: This goes in the globals.h file typedef struct {   unsigned char ServoPWM;   char ServoAngle;   unsigned char DrivePWM;   int TimeOut;   int Current;   int Speed; } sMotor; extern volatile sMotor Motor; This will go in any other file that we want our structure to be accessible from #include <Globals.h> volatile sMotor Motor; This is how to address the variable in the structure #include <Globals.h> volatile sMotor Motor; If you decided to have two distinguishable motors you could do this in the globals.h extern volatile sMotor Motor1; extern volatile sMotor Motor2; Then do this in the other files volatile sMotor Motor1; volatile sMotor Motor2; Helpful Hints In developing an algorithm to detect the line position, we found two basic errors in the coding practice which caused catastrophic errors in line detection. Both of these tips are very basic coding practice. First, when using C code, it usually benefits the user to initialize all variables to some value, especially if computations are involved. Often times when the value wasn't initialized it would seem to acquire a wrong value seemingly from nowhere. Secondly, when doing calculations with arrays, make sure to do calculations with array indices that actually exist. Many times we would make the mistake in our loops of trying to use an index that wasn't assigned a value. Therefore it would acquire an unknown value from memory that caused errors in our calculations.
View full article
1. Overview 2. Hardware 3. Set up the Hardware: Line Scan Camera/Microcontroller Hardware Setup 4. Build the Code 5. Download/Debug/Run 6.Example Code Functions ImageCapture(); ReadADCChannel() Initialize the ADC Header File Definitions Initialize the GPIO Other Tutorials: This tutorial covers the details of obtaining data from the line scan camera on the Kinetis K40 using the TWR-K40X256-KIT evaluation board. General details of the line scan camera not related to the Kinetis can be found in the general Line Scan Camera Theory article. This tutorial will help students familiarize themselves with how to interface the camera with the microcontroller, how to configure GPIO pins to create clock signals and also how to utilize the microcontroller's ADC to read the data from the camera. Outside of control algorithms, configuring the camera is one of the more complex tasks necessary to create a Freescale Cup Vehicle. 1.  Overview In this exercise students will access the line scan camera, create a clock signal and create the initialization pulse which tells the camera to begin the exposure period. This tutorial will not describe line recognition or line following algorithms - these concepts are beyond its scope. Students will: Create the code using Codewarrior Build a project Download the code to the board connect the microcontroller to the camera. Run the program view the camera data, clock and Si pulse on an oscilloscope view the data from the camera in the CodeWarrior Debugger for verification purposes   To successfully complete this exercise, the following software and hardware are required: The K40 Tower card, TWR-K40x256 CodeWarrior for Microcontrollers Freescale Line Scan Camera Motor Board Tower Prototyping board Soldering Iron Solder Tower Elevators USB Cord 2. Hardware   Read the Line Scan Camera Overview article for general information on the camera, ADC, and GPIO microcontroller configuration settings. 3. Set up the Hardware: Line Scan Camera/Microcontroller Hardware Setup It is crucial for an engineer to have the proper test equipment and tools for the job. In this case, without an oscilloscope, students will not be able to verify whether the proper signals are being sent to the camera. 4. Build the Code If there is more than one project in your project view, make sure the proper project is the focus. The most reliable way to do this is to right click the project and choose Build Project as shown below. You can also go to the Project menu and choose the same command. If errors are encountered, look in the Problems view and resolve them. For now ignore any warnings. 5. Download/Debug/Run Download the code to your board, once this process is complete resume the project so that the code runs. If you want more information on how to complete this step see the download debug run section of the Kinetis Blinking Led tutorial. 6.Example Code What will happen: the function ImageCapture() is called in main.c with a pointer to the first element in the array. This function completes the processes necessary to capture images using the camera. To become more familiar with Pointers and Arrays - navigate to the C Programming Tutorial. Knowledge of Pointers and Arrays is a pre-requisite for understanding the Camera Code. Functions The camera code utilizes the following function: within main.c ImageCapture(&Line.RawCameraData[0]); is called to initiate the step of capturing an image into the first position of the array. ImageCapture(); from Camerainterface.c This function captures the images by creating the SI Pulse, and clock signals, capturing the data into an Array using the ADC features of the K40. It calls the function ReadADCChannel() at the proper time which then inputs data from the camera AO line. void ImageCapture(int * ImageData){//this is a pointer to a single character in memory   unsigned char i;   TAOS_SI_HIGH;   TAOS_EXPOSURE_DELAY;   TAOS_CLK_HIGH;   TAOS_EXPOSURE_DELAY;   TAOS_SI_LOW;   TAOS_EXPOSURE_DELAY;   ImageData[0] = (int)ReadADCChannel(19);// inputs data from camera (first pixel)   TAOS_CLK_LOW;   for(i=1;i<128;i++)   {   TAOS_EXPOSURE_DELAY;   TAOS_EXPOSURE_DELAY;   TAOS_CLK_HIGH;   TAOS_EXPOSURE_DELAY;   TAOS_EXPOSURE_DELAY;   ImageData[i] = (int)ReadADCChannel(19); // inputs data from camera (one pixel each time through loop)   TAOS_CLK_LOW;   }   TAOS_EXPOSURE_DELAY;   TAOS_EXPOSURE_DELAY;   TAOS_CLK_HIGH;   TAOS_EXPOSURE_DELAY;   TAOS_EXPOSURE_DELAY;   TAOS_CLK_LOW;  } ReadADCChannel() from readADC.c this function does the analog to digital conversion and returns a value between 0 and 255. It takes the proper ADC channel, in this case 19. Channel 19 corresponds to analog input pin ADC1_DM0 (see page 117 in the K40 Sub-Family Reference Manual). unsigned char ReadADCChannel(unsigned char Channel)   {   ADC1_SC1A = Channel;   while((ADC1_SC1A & ADC_SC1_COCO_MASK) == 0)   {   }   return ADC1_RA;    } Initialize the ADC Before utilizing the ADC it must be calibrated and initialized. The details for how to do this can be found in Chapter 19 Using Peripheral Delay Block (PDB) to Schedule Analog to Digital Converter (ADC) Conversions of the Kinetis Peripheral Module Quick Reference manual. The PDB portions of the code have been removed for the Cup Car Demo Code. Header File Definitions from k40_TOWER_BOARD_SUPPORT.h The following code enables the GPIO on the two pins: #define TAOS_CLK_LOC (1<<28) #define TAOS_SI_LOC (1<<18) Initialize the GPIO From K40_TOWER_BOARD_SUPPORT.c The InitK40GPIO Function sets up the ports for use: Relevant code SIM_SCGC5 = SIM_SCGC5_PORTA_MASK | SIM_SCGC5_PORTB_MASK | SIM_SCGC5_PORTC_MASK | SIM_SCGC5_PORTD_MASK | SIM_SCGC5_PORTE_MASK; //CLK and SI signal PORTC_PCR18 = PORT_PCR_MUX(1) | PORT_PCR_DSE_MASK; PORTE_PCR28 = PORT_PCR_MUX(1) | PORT_PCR_DSE_MASK; //Make Sure the GPIO is setup to be an output GPIOC_PDDR |= LED_E1_LOC | LED_E2_LOC | LED_E3_LOC | TAOS_SI_LOC; GPIOE_PDDR |= TAOS_CLK_LOC; GPIOB_PDDR |= LED_E4_LOC; Other Tutorials: K40:Blinking LED Tutorial K40:Drive DC Motor Tutorial K40:Turning a Servo Tutorial   
View full article
This tutorial covers the details of Blinking an LED on the Kinetis K40 using the TWR-K40X256-KIT evaluation board. It will introduce the evaluation board, and some basic CodeWarrior features. Overview 1. Hardware 2. Set up the Software Development Environment A. Download and Install Codewarrior B. Download and Install Drivers 3. Set up the Hardware: Twr K40x256 Hardware Setup 4. Import the LED Project 5. Build the Code 6. Download/Debug/Run 7. Learning Step: LED Code Description Read/Write Functions Variables Header File Definitions Initialize the GPIO Blink the LED: Other K40 Tutorials: K40 Related Pages Credits / References Overview   In this exercise students will explore a Freescale Cup Car application which targets a Freescale K40 board attached to the Tower System.   Students will: Configure the Software Development Environment Configure the evaluation board hardware Learn how to import example files into a CodeWarrior project Build a project Download and run the code on a Kinetis K40 Tower System board Learn how to utilize the GPIO Peripheral to blink a LED     To successfully complete this exercise, students will need the following board and development environment. The K40 Tower card, TWR-K40x256 CodeWarrior for Microcontrollers USB Cord 1. Hardware     Read the Blink LED overview article for general information on LED circuits, GPIO pins and reference manuals.   2. Set up the Software Development Environment   There are several steps necessary to prepare the evaluation board and PC for microcontroller programming and development. Interfacing the evaluation board with a PC requires downloading and Install the CodeWarrior IDE, as well as the device drivers for programming the microcontroller via USB. A. Download and Install Codewarrior   Before completing this example project, download-and-install-codewarrior-10-1 or the latest version compatible with the twr-k40x256-kit.   B. Download and Install Drivers   In addition to CodeWarrior, it may(needs verified) be necessary to install one or both of the following tools: RAppID initialization tool- RAppID comes on the DVD provided with your evaluation board. In the main directory of the DVD, click on the "TRK_MPC5604B.html" file to open the DVD interface which provides user manuals, software, schematics and documentation for the evaluation board. P&E Microcomputer Systems, Inc drivers- P&E is a a computer driver for the TRK-MPC5604B and Kinetis Tower system device, enabling evaluation board programming via USB through the CodeWarrior debug OSJTAG interface. This driver can be downloaded here in case this isn't found on the disk.   3. Set up the Hardware: Twr K40x256 Hardware Setup   There are several Twr K40x256 hardware configuration steps. Follow the twr-k40x256-hardware-setup instructions before importing the LED Project. 4. Import the LED Project   After the software is successfully downloaded and installed, the next step is to import an existing project into your Workspace. in this case, the LED_BLINK_96MHZ Project. Follow the instructions on the codewarrior-project-import page to import the LED_BLINK_96MHZ project into CodeWarrior. If errors are encountered, look in the Problems view and resolve them. Ignore any warnings. 5. Build the Code   If there is more than one project in your project view, make sure the proper project is the focus. The most reliable way to do this is to right click the project and choose Build Project as shown below. You can also go to the Project menu and choose the same command. By default, the application is set to link to RAM. If you want your program in FLASH, make sure that you have that build configuration enabled:     Make sure you do a "Clean" operation (under the project menu) after you make the configuration change. If you encounter errors, look in the problems view and resolve them. You can ignore any warnings. 6. Download/Debug/Run   If the project builds correctly, it is time to download to the board and watch it work. Ensure that the USB cable that came with the board connects the board to the host computer’s USB port. There are multiple ways to issue the Debug command. Right click the project in the projects view and choose Debug As->CodeWarrior Download. Alternatively, y go to the Run menu and choose Debug (F11). Click the Resume button and your should see the LED blinking! Click the Pause button to stop execution. Click the Terminate button to end debugging. 7. Learning Step: LED Code Description Read/Write   If the LED was on Port C, Bit 7 we might have code like: #define LED_E1_Location(1<<7)   For example, to toggle a pin the following code might be used: GPIOC_PSOR=LED_E1_LOC     "Sets" the LED located at "E1" high.   the syntax means the following GPIOC refers to Port C   "Set" is one of three commonly utilized commands for GPIO control. There are also commands for "Clear" and "Toggle."   Command: "GPIOC_PSOR" literally means PORT SET OUTPUT REGISTER which SETS a pin high Command: "GPIOC_PCOR" clears a pin, PORT CLEAR OUTPUT REGISTER which CLEARS a pin to the "low" state Command: "GPIOC_PTOR" toggles a pin opposite of the current state   the « is a "shift" command which is discussed in the c-programming-for-embedded-systems. You can alter the raw register as well using a MASK but the dedicated set/clear/toggle registers are more straightforward.   **NEEDS UPDATED ** Hardware Chip Port/Pin Comment SW3 PT cell-content SW4 cell-content cell-content Functions   The following functions can access the LED; //Where n is the LED number LED_En_TOGGLE;  //will toggle a LED to a different state LED_En_ON; // turns the LED ON LED_En_OFF // turns the LED OFF Variables   Locations of the LED's LED_E1_LOC LED_E2_LOC LED_E3_LOC LED_E4_LOC Header File Definitions   from k40_TOWER_BOARD_SUPPORT.h //The E1 LED is on Port C, Bit 7 #define LED_E1_LOC (1<<7) #define LED_E2_LOC (1<<8) #define LED_E3_LOC (1<<9) #define LED_E4_LOC (1<<11)    //There are dedicated set and clear registers.    //Write a one to PSOR Sets the Bits, Writing to PCOR clears bits.    //Toggling a bit can be done with the PTOR register    //You can access the raw register as well -> PDOR |= My Bit    //but the dedicated bit set/clear/toggle registers are easier!    //Also, The cathode of the LEDs are towards the port pin! This means    //you have to turn the port off to get the LED to turn the pin on. #define LED_E1_OFF   GPIOC_PSOR=LED_E1_LOC #define LED_E1_ON   GPIOC_PCOR=LED_E1_LOC #define LED_E1_TOGGLE   GPIOC_PTOR=LED_E1_LOC #define LED_E2_OFF   GPIOC_PSOR=LED_E2_LOC #define LED_E2_ON   GPIOC_PCOR=LED_E2_LOC #define LED_E2_TOGGLE   GPIOC_PTOR=LED_E2_LOC #define LED_E3_OFF   GPIOC_PSOR=LED_E3_LOC #define LED_E3_ON   GPIOC_PCOR=LED_E3_LOC #define LED_E3_TOGGLE   GPIOC_PTOR=LED_E3_LOC #define LED_E4_OFF   GPIOB_PSOR=LED_E4_LOC #define LED_E4_ON   GPIOB_PCOR=LED_E4_LOC #define LED_E4_TOGGLE   GPIOB_PTOR=LED_E4_LOC Initialize the GPIO   From K40_TOWER_BOARD_SUPPORT.c void InitK40GPIO() {    SIM_SCGC5 = SIM_SCGC5_PORTA_MASK | SIM_SCGC5_PORTB_MASK | SIM_SCGC5_PORTC_MASK | SIM_SCGC5_PORTD_MASK | SIM_SCGC5_PORTE_MASK;    //To use a Port, its Clock must be enabled!!    //Lets just enable the clocks for ALL of the ports    //Important! Each IO pin has a dedicated 32-bit Register to set it up (Selection GPIO vs peripheral, IRQ, Etc.)    //Setup port C7,C8,C9 and B11 as GPIO and enable High Drive Strength    PORTC_PCR7 = PORT_PCR_MUX(1) | PORT_PCR_DSE_MASK;  //Enable GPIO on on the pin    PORTC_PCR8 = PORT_PCR_MUX(1) | PORT_PCR_DSE_MASK;  //Enable GPIO on on the pin    PORTC_PCR9 = PORT_PCR_MUX(1) | PORT_PCR_DSE_MASK;  //Enable GPIO on on the pin    PORTB_PCR11 = PORT_PCR_MUX(1) | PORT_PCR_DSE_MASK;  //Enable GPIO on on the pin    PORTC_PCR18 = PORT_PCR_MUX(1) | PORT_PCR_DSE_MASK;    PORTE_PCR28 = PORT_PCR_MUX(1) | PORT_PCR_DSE_MASK;    //Make Sure the GPIO is setup to be an output    GPIOC_PDDR |= LED_E1_LOC | LED_E2_LOC | LED_E3_LOC;    GPIOB_PDDR |= LED_E4_LOC;    LED_E1_OFF;    LED_E2_OFF;    LED_E3_OFF;    LED_E4_OFF; } Blink the LED:   Within Main.c or any other C file created, Blink the LED's using the following functions: LED_E1_TOGGLE; LED_E1_ON; LED_E2_OFF; Other K40 Tutorials:   K40 Related Pages   K40: Turning A Servo Tutorial   K40: Drive DC Motor Tutorial Kinetis K40 TWR-K40X256 K40: Blinking LED Credits / References   Some of the content from this tutorial originated from:   Shawn Moffit: Electrical Engineering, Penn State University for - K40 Code   Processor Expert Hands-On Lab Rev. 1.0, 05/2011 by Jim Trudeau, Freescale Semiconductor, Inc. for - some text descriptions of steps Original Attachment has been moved to: LED_BLINK_96MHZ.zip
View full article
The file contains the rules for The NXP Cup EMEA 2016-2017 edition of the challenge. Revision 1 dated 13-Jul-2016 For any question : marion.thierry@nxp.com
View full article
INTRODUCTION Hi everyone, Making/Developing/Porting a Bootloader is a tedious task for newbies (even for professionals) and inexperienced hobbyists who wish to use them on their custom hardware for rapid prototyping. After searching a lot on different forums I came to a conclusion that I cant develop a bootloader just like that so my next option was porting ,that too wasnt easy if you are going with old bootloaders with limited support. I then found a very easy and efficient way of rapid software development platform that can be used on almost any IDE (Keil,Codewarrior,KDS,etc.) and can be used to develop softwares like USB MSD Bootloaders,Serial Bootloaders and other applications for almost all Freedom Development Boards ,Freescale Kinetis MCUs (on a Custom Development Board ) with minimal ARM Programming Knowledge, which is perfect for newbies like me who are just starting with ARM Development using freescale or other boards.See Welcome to the homepage of the µTasker operating system with integrated TCP/IP stack, USB and target device simulator Now my project was to make custom board using MK22DX256VLF5 (48 LQFP) MCU ,my board is a rather a simple one using basic filtering circuits for powering the MCU and almost all the pinouts given as hardware pins on the dev board.Somehow I was able to flash my first blink code using Keil IDE using the OpenSDA circuitry of FRDM-KL25Z (J-11 trace cut ) with CMSIS-DAP firmware (OpenSDA app ) loaded on to it using SWD Programming. With the steps mentioned below I'll show you how to port a Mass Storage Device (MSD) Bootloader using uTasker project from scratch. REQUIREMENTS Programmer(Hardware) or Emulated Programmer(OpenSDA apps): Segger Jlink, P&E Multilink ,OpenSDA Emulators (Jlink-SDA, CMSIS-DAP,USBDM ) IDE :Keil,Codewarrior, Kinetis Design Studio etc. (I prefer CW 10.6 ) Target MCU: Choose any MCU between Kinetis,Coldfire V2,STM32  (I am using Freescale Kinetis MK22DX256VLF5 ,48 LQFP ) refer - http://www.utasker.com/ PROCEDURE 1. Lets start by downloading the uTasker project/framwork (for Kinetis ) from µTasker Kinetis Developer's Page . Then extract and copy the folder to your CW workspace ,import the project to CodeWarrior IDE, It should look like this. (I am using version 14-9-2015)   2.Next Select "uTaskerSerialLoader_Flash" from the Five build configurations (refer http://www.utasker.com/docs/uTasker/uTaskerSerialLoader.PDF  ).uTaskerBM_Loader is described in http://www.utasker.com/docs/uTasker/uTasker_BM_Loader.pdf This is a very small loader alternative that works together with an initial application. uTaskerV1.4_BM_FLASH is the application to build so that it can be loaded to a loader (including the USB-MSD one). uTaskerV1.4 is a 'stand-alone' version of the application that doesn't work together with a loader (and doesn't need a loader).If you want to build application to load using the USB-MSD loader you need to use uTaskerV1.4_BM_FLASH. after that find the files config.h and ap_hw_kinetis.h.These files define the type of MCU you use. 3.In config.h Select your board or MCU type or the closest MCU resembling the architecture of your own MCU. My MCU  MK22DX256VLF5 was not there so with a little help from mjbcswitzerland  I chose TWR_K21D50M Board settings as TWR-K21D50M module is a development board for the Freescale Kinetis K11, K12, K21 and K22 MCUs. (Note : Be sure to remove or comment any other defined boards ) After Selecting the Board/MCU scroll down to find USB_INTERFACE and USB_MSD_LOADER and make sure that these two are defined (not commented ).This is necessary to enable USB enumeration as Mass storage device. Also comment the following if already defined : HID_LOADER KBOOT_HID_LOADER USB_MSD_HOST This is necessary as we are using our Bootloader in MSD Device Mode not in MSD Host Mode. Also we arent using HID_LOADER and KBOOT. Now open  ap_hw_kinetis.h and Find your selected MCU (in my case its TWR_K21D50M ) So, Find the String "TWR_K21D50M" (or whatever your MCU is ) and see if the follwing lines are defined. #define OSC_LOW_GAIN_MODE #define CRYSTAL_FREQUENCY    8000000  #define _EXTERNAL_CLOCK      CRYSTAL_FREQUENCY #define CLOCK_DIV            4                                      or    #if(..........)         #define CLOCK_MUL        48                                            #define SYSTEM_CLOCK_DIVIDE 2                                      #else         #define CLOCK_MUL        24 #endif     #define USB_CLOCK_GENERATED_INTERNALLY Here comes an integral part of USB MSD Bootloading/Programming.You must be wondering about CRYSTAL_FREQUENCY  8000000 and  CLOCK_DIV   4  .This is the frequency of an external crystal oscillator  (8mhz) connected between EXTAL0 and XTAL0 pins of the Target MCU.If your MCU has an internal oscillator then check whether the latter is defined. refer- https://cache.freescale.com/files/microcontrollers/doc/app_note/AN4905.pdf          http://www.utasker.com/kinetis/MCG.html There are two ways to be able to use USB: 1. Use a crystal between EXTAL0 and XTAL0 - usually 8MHz is used. (with or without load capacitor -both worked for me ) 2. Use a 48MHz oscillator on the USB-CLKIN pin. First one is easier and it worked for me.Since my MCU doesnt have an internal oscillator I have used and External 8Mhz crystal. If you want to use a 16Mhz crystal then just make the following changes : #define CRYSTAL_FREQUENCY    8000000 #define _EXTERNAL_CLOCK      CRYSTAL_FREQUENCY #define CLOCK_DIV            4                                 TO #define CRYSTAL_FREQUENCY    16000000 #define _EXTERNAL_CLOCK      CRYSTAL_FREQUENCY #define CLOCK_DIV            8 Note: The CLOCK_DIV should be such that it prescales the crystal frequency to range of 2-4MHz. Here is the clocking diagram of My MCU.The next diagram shows an oscillator crystal connected externally to my dev board. Next search for "PIN_COUNT" under your corresponding MCU/Board (mine is TWR_K21D50M).My MCU is 48 LQFP with 256kb flash and 32kb SRAM (you have to change them according to your MCU ).So I have changed the following lines                              from   #define PIN_COUNT           PIN_COUNT_121_PIN                         #define SIZE_OF_FLASH       (512 * 1024)                          #define SIZE_OF_RAM          (64 * 1024)                              to   #define PIN_COUNT           PIN_COUNT_48_PIN                      #define SIZE_OF_FLASH       (256 * 1024)                              #define SIZE_OF_RAM          (32 * 1024)  Next if you search for your MCU/Board (in this case TWR_K21D50M) ,you will find this line : #define UART2_ON_E This defines the alternative port for UART2,since many boards doesnt have PORTE ,it can be chaned to other ports. [its not important though] Note : When building the serial loader for a device with small RAM size reduce the define #define TX_BUFFER_SIZE (5512) to 512 bytes so the buffer can be allocated (the large size was used only for some debugging output on a larger device) [loader version :14.9.2015] Now search for the String "BLINK_LED" under your corresponding MCU/Board ( mine is TWR_K21D50M ) .The uTasker Bootloader has a special function ,whenever it is in MSD/LOADER mode it blinks a test LED on the board.This is not important but it can be used for debugging purposes.I have a test LED on my board at PORTB16 .You can also specify hardare pins to force bootloader mode and to stop watchdog timer if you pull SWITCH_3 and SWITCH_2 down to ground respectively.I am setting SWITCH_3 and SWITCH_2 as PORTD7 and PORTD6 respectively. Now on the toolbars go to Project > Properties > C/C++ Build > Settings > Tool Settings > Target Processor :Change it to your MCU type (mine is cortex-m4 ) .Next go to Linker >General and change the linker script file to match your MCU's flash,RAM,Type.I have set mine to K_256_32.ld (Kinetis K type processor with 256kb flash and 32 kb RAM) Apply your changes.Now you are ready to go. 4.  Build your project under SerialLoader_FLASH configuration .If there are no compilation errors then you have done it! (if there are then recheck everything with this guide ) Now Click the Flash programmer icon a and Select Flash File to Target. (if your not getting the icon switch to "DEBUG" perspective view ) Now you may choose your Programmer (or emulated programmer )[connection tab] ,select the correct Flash configuration file ,then browse for the binary file that has been generated under C:\Users\<computer user>\workspace\Kinetis_14-9-2015\Applications\uTaskerSerialBoot\KinetisCodeWarrior\uTaskerSerialBoot_FLASH\uTaskerSerialBoot.bin and Click on "Erase and Program". You may skip Step 5 and go to Step 6. 5.I am using the OpenSDA circuitry of my FRDM-KL25Z (J-11 trace cut ) as a programmer using J-link OpenSDA app. Download the app from SEGGER - The Embedded Experts for RTOS and Middleware, Debug Probes and Production Programmers - OpenSDA / OpenSDA V2 depending on your OpenSDA version (FRDM KL25Z has OpenSDAv1). Refer - Using the Freedom Board as SWD Programmer | MCU on Eclipse 5.1.First Enter bootloader mode and Flash the Jlink sda app into it.Connect the SWD wires from the board to your  Target MCU/Board ,also connect the target board        to the external oscillator.Also connect the FRDM's OpenSDA through USB. (A drive with the name JLINK Should come )                                          5.2. Go to Flash File to target and under connections tab click new. give any name and click new under Target Tab.Then select the target type (your target MCU ,mine is                      K22DX256M5).Then check Execute Reset under Initialization Tab. Click finish.    Now you'll get the option to select connection type ,then choose J-Link/J-Trace for ARM and change the Debug port interface to SWD .If you get the error :connection name is not        unique then just change the name (I have used jlink1).Click Finish.     Now I have set up my connections so I can flash the MCU with Jlink app on my OpenSDA circuitry. 6. Now to verify USB Enumeration of your Custom Board ,connect it to PC using USB and you should get a drive with the name UPLOAD_DISK.
View full article
Freescale Cup 2016 Worldwide Rules
View full article
EGR280 sophomore design and ECE470/570 Microprocessor based system design at Oakland University (in South East Michigan). Using CW HC12(x) special edition and Wytec Dragon12 dev boards.
View full article
Footage from the technical inspection taken during The Freescale Cup 2015 Worldwide Finals. Credit: Fraunhofer IIS         
View full article
Video footage highlights taken during The Freescale Cup Worldwide Finals 2015 Award Ceremony Credit: Fraunhofer IIS
View full article
Footage highlights of the Freescale Cup Worldwide finals race 2015. Credit: Fraunhofer IIS
View full article