rpiPWM.h
Go to the documentation of this file.
00001 #ifndef RPIPWM_H
00002     #define PRIPWM_H
00003 #include <stdio.h>
00004 #include <stdlib.h>
00005 #include <limits.h>
00006 #include <unistd.h>
00007 #include <sys/mman.h>
00008 #include <sys/types.h>
00009 #include <sys/stat.h>
00010 #include <fcntl.h>
00011 /***********************************************************************
00012  * Author: Hussam al-Hertani (Hertaville.com)
00013  * Others are free to modify and use this code as they see fit so long as they
00014  * give credit to the author.
00015  * 
00016  * The author is not liable for any kind of damage caused by this software. 
00017  * 
00018  * Acknowledgements: This 'C++' class is based on 'C' code available from :
00019  * - code from http://elinux.org/RPi_Low-level_peripherals 
00020  * - http://www.raspberrypi.org/phpBB3/viewtopic.php?t=8467&p=124620 for PWM initialization
00021  * - frank's code...http://www.frank-buss.de/raspberrypi/pwm.c
00022  * - Gertboard's C source code 
00023  * 
00024  * The rpiPWM class provides a direct memory mapped (register-based)
00025  * interface to the PWM1 hardware on the Raspberry Pi's BCM2835 SOC.
00026  * The BCM2835 SOC was two PWM subsystems, PWM1 & PWM2. This code will 
00027  * enable access to the PWM1 subsystem which outputs the PWM signal on
00028  * GPIO18 (ALT5). 
00029  * 
00030  * The class enables setting the Frequency (Max 19.2MHz), PWM resolution(4095),
00031  * DutyCycle and PWM Mode to be used. The Duty Cycle can be set as a 
00032  * percentage (setDutyCycle() or setDutyCycleForce()) or as a  function 
00033  * of the PWM Resoultion (setDutyCycleCount())
00034  * 
00035  * Two PWM modes exist: 
00036  *  - MSMODE - This is the traditional PWM Mode i.e. if PWM Resolution 
00037  *             (counts) is 1024 and the dutyCycle (Pulse on time) is 512 (in counts or 50%)
00038  *             then the waveform would look like:
00039  *             |||||||||||||||||_________________
00040  *             MSMODE is ideal for servos and other applications that 
00041  *             require classical PWM waveforms
00042  * - PWMMODE - Is a slightly modified version of the traditional PWM Mode 
00043  *             described above. The duty cycle or ON time is still unchanged
00044  *             within the period but is distributed across the entire period instead
00045  *             on being concentrated in the first part of the period..i.e.if PWM Resolution 
00046  *             (counts) is 1024 and the dutyCycle (Pulse on time) is 512 (in counts or 50%)
00047  *             then the waveform would look like:     
00048  *             |_|_|_|_|_|_|_|_|_|_|_|_|_|_|_|_|_
00049  *             This mode is ideal if you want to pass the signal through 
00050  *             a low pass filter to obtain an analog signal equivalent to the . The even 
00051  *             distibution of the ON time through the entire period 
00052  *             significantly reduces ripple caused by using a simple RC
00053  *             low pass filter     
00054  *
00055  * When setting the frequency via the constructor or 'setFrequency' method, one is strictly
00056  * requesting a particular frequency. The code will do its best to get as close as possible to 
00057  * the requested frequency but it is likely to not create a PWM at the exact requested Frequency.
00058  * As an example say that we want to create a PWM waveform with a resolution of 256 counts (8-bit)
00059  * and a frequency of 8KHz....We get the divisor using the following algorithm
00060  *
00061  * Waveform  period = 1 / 8KHz = 0.125ms
00062  * Duration of a single count = period/256 = 0.125ms / 256 = 0.488us
00063  * Frequency of a single count = 1 / Duration of a single count = 1 / 0.488us = 2.048MHz
00064  * Divisor value = floor (PWM Clock Frequency / Frequency of a single count) = floor (19.2MHz / 2.048MHz) = floor(9.375) = 9
00065  *
00066  * With a Divisor of 9 Actual Waveform Frequency = 1/((1/(19.2MHz/9))*256) = 8.333 KHz
00067  *
00068  * The actual Frequency will generally deviate further from the desired frequency as the count value (PWM resolution)
00069  * increases i.e. As an example say that we want to create a PWM waveform with a resolution of 1024 counts (10-bit)
00070  * and the same frequency as the above example:
00071  *
00072  * Waveform  period = 1 / 8KHz = 0.125ms
00073  * Duration of a single count = period/1024 = 0.125ms / 1024 = 122.070ns
00074  * Frequency of a single count = 1 / Duration of a single count = 1 / 122.070ns = 8.192MHz
00075  * Divisor value = floor (PWM Clock Frequency / Frequency of a single count) 
00076  *               = floor (19.2MHz / 8.192MHz) = floor(2.34) = 2
00077  *
00078  * With a Divisor of 2, Actual Waveform Frequency = 1/((1/(19.2MHz/2))*1024) = 9.375KHz
00079  * 
00080  * DIVISOR MUST BE AT LEAST 2....SO PICK YOUR COUNT AND DESIRED FREQUENCY VALUES CAREFULLY!!!!! 
00081  * i.e MAXIMUM FREQUENCY FOR 10-BIT RESOLUTION (COUNT=1024) IS 9.375KHz
00082  *  &  MAXIMUM FREQUENCY FOR 8-BIT RESOLUTION (COUNT=256) IS 37.5KHz
00083  *
00084  * WARNING:    The RPI uses the PWM1 subsystem to produce audio. As such
00085  *             please refrain from playing audio on the RPI while this code 
00086  *             is running.
00087  * *********************************************************************/
00088 class rpiPWM {
00089 
00090 public:
00091   rpiPWM();
00092   // default constructor configures GPIO18 for PWM and Frequency 1000Hz,
00093   // PWM resolution (counts) 256, Duty Cycle 50% and PWM mode is 'PWMMODE'
00094   rpiPWM(double Hz, unsigned int cnts, double duty,  int m);
00095   //overloaded constructor..allows user to set initial values for Frequency,
00096   //PWM resolution, Duty Cycle and PWM mode.
00097   ~rpiPWM();
00098   // Destructor....safely releases all mapped memory and puts all used peripherals
00099   // (PWM clock, PWM peripheral and GPIO peripheral in their initial states
00100   unsigned int setFrequency(const double &hz);
00101   // Sets Frequency and reinitializes PWM peripheral
00102   unsigned int setCounts(const unsigned int &cnts);
00103   // Sets PWM resolution (counts) and reinitializes PWM peripheral
00104   unsigned int setDutyCycle(const double &duty, int pwm_no);
00105   // Sets Duty Cycle as a Percentage (Fast)
00106   unsigned int setDutyCycleCount(const unsigned int &cnts, int pwm_no);
00107   // Sets Duty Cycle as a count value (Fast) i.e. if counts is 1024
00108   // and 'duty' is set to 512, a 50% duty cycle is achieved
00109   unsigned int setDutyCycleForce(const double &duty, const  int &m, int pwm_no);
00110   // disables PWM peripheral first,
00111   //Sets Duty Cycle as a Percentage and PWM mode...
00112   // then enables PWM peripheral
00113   unsigned int setMode(const  int &m);
00114   // sets PWM mode...calls 'setDutyCycleForce()'
00115   
00116   void setDirection(int pwm_mod, int _direction);
00117   
00118   double getFrequency() const;
00119   // returns current Frequency of PWM waveform
00120   double getDutyCycle() const;
00121   // returns current DutyCycle (as a %) of PWM waveform
00122   int getCounts() const;
00123   // returns PWM resolution 
00124   int getDivisor() const;
00125   //returns Divisor value used to set the period per count
00126   //as a function of the default PWM clock Frequency of 19.2MHz
00127   int getMode() const;
00128   //returns (1) if current PWM mode is 'PWMMODE' or (2) if current PWM mode
00129   //is 'MSMODE'
00130   
00131   //Public constants
00132   static const int PWMMODE = 1;
00133   static const int MSMODE = 2;
00134   //Two PWM modes
00135   static const int ERRFREQ = 1;
00136   static const int ERRCOUNT = 2;
00137   static const int ERRDUTY = 3;
00138   static const int ERRMODE = 4;
00139   //Error Codes
00140   
00141 private:
00142   //Private constants
00143   static const int BCM2708_PERI_BASE = 0x3F000000;//0x20000000;
00144   static const int PWM_BASE = (BCM2708_PERI_BASE + 0x20C000); /* PWM controller */
00145   static const int CLOCK_BASE = (BCM2708_PERI_BASE + 0x101000); /* Clock controller */
00146   static const int GPIO_BASE = (BCM2708_PERI_BASE + 0x200000); /* GPIO controller */
00147   //Base register addresses
00148   static const int PWM_CTL = 0;
00149   static const int PWM_RNG1 = 4;
00150   static const int PWM_DAT1 = 5;
00151   static const int PWM_RNG2 = 8;
00152   static const int PWM_DAT2 = 9;
00153   static const int PWMCLK_CNTL= 40;
00154   static const int PWMCLK_DIV = 41;
00155 
00156   // Register addresses offsets divided by 4 (register addresses are word (32-bit) aligned 
00157   static const int BLOCK_SIZE = 4096;
00158   // Block size.....every time mmap() is called a 4KB 
00159   //section of real physical memory is mapped into the memory of
00160   //the process
00161 
00162   
00163   volatile unsigned *mapRegAddr(unsigned long baseAddr);
00164   // this function is used to map physical memory 
00165   void configPWMPin();
00166   //this function sets GPIO18 to the alternat function 5 (ALT5)
00167   // to enable the pin to output the PWM waveforms generated by PWM1
00168   void configPWM();
00169   //This function is responsible for the global configuration and initialixation
00170   //of the the PWM1 peripheral
00171   
00172   double frequency; // PWM frequency
00173   double dutyCycle; //PWM duty Cycle (%)
00174   unsigned int counts; // PWM resolution
00175   unsigned int divisor; // divisor value
00176   int mode;  // PWM mode
00177   int direction0, dirLast0, direction1, dirLast1;
00178   volatile unsigned *clk, *pwm, *gpio; // pointers to the memory mapped sections 
00179   //of our process memory 
00180   
00181 };
00182 #endif


evarobot_driver
Author(s): Mehmet Akcakoca
autogenerated on Fri Feb 12 2016 01:15:19