PololuLedStrip.h
Go to the documentation of this file.
00001 #pragma once
00002 
00003 #include <Arduino.h>
00004 
00005 #if defined(__AVR__)
00006 #include <avr/io.h>
00007 #include <avr/interrupt.h>
00008 #include <util/delay.h>
00009 
00010 #define __enable_irq sei
00011 #define __disable_irq cli
00012 
00013 #if !(F_CPU == 8000000 || F_CPU == 16000000 || F_CPU == 20000000)
00014 #error "On an AVR, this version of the PololuLedStrip library only supports 8, 16 and 20 MHz."
00015 #endif
00016 
00017 #elif defined(__arm__)
00018 
00019 #if !(F_CPU == 84000000)
00020 #error "On an ARM, this version of the PololuLedStrip library only supports 84 MHz."
00021 #endif
00022 
00023 #endif
00024 
00025 namespace Pololu
00026 {
00027   #ifndef _POLOLU_RGB_COLOR
00028   #define _POLOLU_RGB_COLOR
00029   typedef struct rgb_color
00030   {
00031     unsigned char red, green, blue;
00032   } rgb_color;
00033   #endif
00034 
00035   class PololuLedStripBase
00036   {
00037     public:
00038     static bool interruptFriendly;
00039     void virtual write(rgb_color *, unsigned int count) = 0;
00040   };
00041 
00042   template<unsigned char pin> class PololuLedStrip : public PololuLedStripBase
00043   {
00044     public:
00045     void virtual write(rgb_color *, unsigned int count);
00046   };
00047 
00048   #if defined(__AVR_ATmega32U4__)
00049   // ATmega32U4-based boards such as the Arduino Leonardo
00050 
00051   const unsigned char pinBit[] =
00052   {
00053     2, 3, 1, 0, 4, 6, 7, 6,  // Pins 0-7
00054     4, 5, 6, 7, 6, 7,        // Pins 8-13
00055     3, 1, 2, 0,              // Pins 14-17
00056     7, 6, 5, 4, 1, 0,        // Pins 18-23
00057     4, 7, 4, 5, 6, 6,        // Pins 24-29
00058   };
00059 
00060   const unsigned char pinAddr[] =
00061   {
00062     _SFR_IO_ADDR(PORTD),
00063     _SFR_IO_ADDR(PORTD),
00064     _SFR_IO_ADDR(PORTD),
00065     _SFR_IO_ADDR(PORTD),
00066     _SFR_IO_ADDR(PORTD),
00067     _SFR_IO_ADDR(PORTC),
00068     _SFR_IO_ADDR(PORTD),
00069     _SFR_IO_ADDR(PORTE),
00070 
00071     _SFR_IO_ADDR(PORTB),
00072     _SFR_IO_ADDR(PORTB),
00073     _SFR_IO_ADDR(PORTB),
00074     _SFR_IO_ADDR(PORTB),
00075     _SFR_IO_ADDR(PORTD),
00076     _SFR_IO_ADDR(PORTC),
00077 
00078     _SFR_IO_ADDR(PORTB),
00079     _SFR_IO_ADDR(PORTB),
00080     _SFR_IO_ADDR(PORTB),
00081     _SFR_IO_ADDR(PORTB),
00082 
00083     _SFR_IO_ADDR(PORTF),
00084     _SFR_IO_ADDR(PORTF),
00085     _SFR_IO_ADDR(PORTF),
00086     _SFR_IO_ADDR(PORTF),
00087     _SFR_IO_ADDR(PORTF),
00088     _SFR_IO_ADDR(PORTF),
00089 
00090     _SFR_IO_ADDR(PORTD),
00091     _SFR_IO_ADDR(PORTD),
00092     _SFR_IO_ADDR(PORTB),
00093     _SFR_IO_ADDR(PORTB),
00094     _SFR_IO_ADDR(PORTB),
00095     _SFR_IO_ADDR(PORTD),
00096   };
00097 
00098   #elif defined(__AVR__) && !defined(NUM_DIGITAL_PINS) || NUM_DIGITAL_PINS == 20
00099   // ATmega168/328-based boards such as the Arduino Uno or Baby Orangutan B-328
00100 
00101   const unsigned char pinBit[] =
00102   {
00103     0, 1, 2, 3, 4, 5, 6, 7,  // PORTD
00104     0, 1, 2, 3, 4, 5,        // PORTB
00105     0, 1, 2, 3, 4, 5, 6,     // PORTC
00106   };
00107 
00108   const unsigned char pinAddr[] =
00109   {
00110     _SFR_IO_ADDR(PORTD),
00111     _SFR_IO_ADDR(PORTD),
00112     _SFR_IO_ADDR(PORTD),
00113     _SFR_IO_ADDR(PORTD),
00114     _SFR_IO_ADDR(PORTD),
00115     _SFR_IO_ADDR(PORTD),
00116     _SFR_IO_ADDR(PORTD),
00117     _SFR_IO_ADDR(PORTD),
00118     _SFR_IO_ADDR(PORTB),
00119     _SFR_IO_ADDR(PORTB),
00120     _SFR_IO_ADDR(PORTB),
00121     _SFR_IO_ADDR(PORTB),
00122     _SFR_IO_ADDR(PORTB),
00123     _SFR_IO_ADDR(PORTB),
00124     _SFR_IO_ADDR(PORTC),
00125     _SFR_IO_ADDR(PORTC),
00126     _SFR_IO_ADDR(PORTC),
00127     _SFR_IO_ADDR(PORTC),
00128     _SFR_IO_ADDR(PORTC),
00129     _SFR_IO_ADDR(PORTC),
00130     _SFR_IO_ADDR(PORTC),
00131   };
00132 
00133   #elif defined(__AVR__) && NUM_DIGITAL_PINS == 70
00134   // ATmega2560-based boards such as the Arduino Mega 2560
00135 
00136   const unsigned char pinBit[] =
00137   {
00138     0, 1, 4, 5, 5, 3, 3, 4, 5, 6,
00139     4, 5, 6, 7, 1, 0, 1, 0, 3, 2,
00140     1, 0, 0, 1, 2, 3, 4, 5, 6, 7,
00141     7, 6, 5, 4, 3, 2, 1, 0, 7, 2,
00142     1, 0, 7, 6, 5, 4, 3, 2, 1, 0,
00143     3, 2, 1, 0, 0, 1, 2, 3, 4, 5,
00144     6, 7, 0, 1, 2, 3, 4, 5, 6, 7,
00145   };
00146 
00147   const unsigned char pinAddr[] =
00148   {
00149     _SFR_IO_ADDR(PORTE),
00150     _SFR_IO_ADDR(PORTE),
00151     _SFR_IO_ADDR(PORTE),
00152     _SFR_IO_ADDR(PORTE),
00153     _SFR_IO_ADDR(PORTG),
00154     _SFR_IO_ADDR(PORTE),
00155     _SFR_IO_ADDR(PORTH),
00156     _SFR_IO_ADDR(PORTH),
00157     _SFR_IO_ADDR(PORTH),
00158     _SFR_IO_ADDR(PORTH),
00159     _SFR_IO_ADDR(PORTB),
00160     _SFR_IO_ADDR(PORTB),
00161     _SFR_IO_ADDR(PORTB),
00162     _SFR_IO_ADDR(PORTB),
00163     _SFR_IO_ADDR(PORTJ),
00164     _SFR_IO_ADDR(PORTJ),
00165     _SFR_IO_ADDR(PORTH),
00166     _SFR_IO_ADDR(PORTH),
00167     _SFR_IO_ADDR(PORTD),
00168     _SFR_IO_ADDR(PORTD),
00169     _SFR_IO_ADDR(PORTD),
00170     _SFR_IO_ADDR(PORTD),
00171     _SFR_IO_ADDR(PORTA),
00172     _SFR_IO_ADDR(PORTA),
00173     _SFR_IO_ADDR(PORTA),
00174     _SFR_IO_ADDR(PORTA),
00175     _SFR_IO_ADDR(PORTA),
00176     _SFR_IO_ADDR(PORTA),
00177     _SFR_IO_ADDR(PORTA),
00178     _SFR_IO_ADDR(PORTA),
00179     _SFR_IO_ADDR(PORTC),
00180     _SFR_IO_ADDR(PORTC),
00181     _SFR_IO_ADDR(PORTC),
00182     _SFR_IO_ADDR(PORTC),
00183     _SFR_IO_ADDR(PORTC),
00184     _SFR_IO_ADDR(PORTC),
00185     _SFR_IO_ADDR(PORTC),
00186     _SFR_IO_ADDR(PORTC),
00187     _SFR_IO_ADDR(PORTD),
00188     _SFR_IO_ADDR(PORTG),
00189     _SFR_IO_ADDR(PORTG),
00190     _SFR_IO_ADDR(PORTG),
00191     _SFR_IO_ADDR(PORTL),
00192     _SFR_IO_ADDR(PORTL),
00193     _SFR_IO_ADDR(PORTL),
00194     _SFR_IO_ADDR(PORTL),
00195     _SFR_IO_ADDR(PORTL),
00196     _SFR_IO_ADDR(PORTL),
00197     _SFR_IO_ADDR(PORTL),
00198     _SFR_IO_ADDR(PORTL),
00199     _SFR_IO_ADDR(PORTB),
00200     _SFR_IO_ADDR(PORTB),
00201     _SFR_IO_ADDR(PORTB),
00202     _SFR_IO_ADDR(PORTB),
00203     _SFR_IO_ADDR(PORTF),
00204     _SFR_IO_ADDR(PORTF),
00205     _SFR_IO_ADDR(PORTF),
00206     _SFR_IO_ADDR(PORTF),
00207     _SFR_IO_ADDR(PORTF),
00208     _SFR_IO_ADDR(PORTF),
00209     _SFR_IO_ADDR(PORTF),
00210     _SFR_IO_ADDR(PORTF),
00211     _SFR_IO_ADDR(PORTK),
00212     _SFR_IO_ADDR(PORTK),
00213     _SFR_IO_ADDR(PORTK),
00214     _SFR_IO_ADDR(PORTK),
00215     _SFR_IO_ADDR(PORTK),
00216     _SFR_IO_ADDR(PORTK),
00217     _SFR_IO_ADDR(PORTK),
00218     _SFR_IO_ADDR(PORTK),
00219   };
00220 
00221   #endif
00222 
00223   template<unsigned char pin> void __attribute__((aligned(16))) PololuLedStrip<pin>::write(rgb_color * colors, unsigned int count)
00224   {
00225     #if defined(__AVR__)
00226     digitalWrite(pin, LOW);
00227     pinMode(pin, OUTPUT);
00228 
00229     #elif defined(__arm__)
00230     Pio * port = g_APinDescription[pin].pPort;
00231     uint32_t pinValue = g_APinDescription[pin].ulPin;
00232     PIO_SetOutput(port, pinValue, LOW, 0, 0);
00233 
00234     #endif
00235 
00236     __disable_irq();   // Disable interrupts temporarily because we don't want our pulse timing to be messed up.
00237 
00238     while(count--)
00239     {
00240       // Send a color to the LED strip.
00241       // The assembly below also increments the 'colors' pointer,
00242       // it will be pointing to the next color at the end of this loop.
00243       #if defined(__AVR__)
00244       asm volatile(
00245         "ld __tmp_reg__, %a0+\n"         // Advance pointer from red to green.
00246         "ld __tmp_reg__, %a0\n"          // Read the green component and leave the pointer pointing to green.
00247         "rcall send_led_strip_byte%=\n"  // Send green component.
00248         "ld __tmp_reg__, -%a0\n"         // Read the red component and leave the pointer at red.
00249         "rcall send_led_strip_byte%=\n"  // Send green component.
00250         "ld __tmp_reg__, %a0+\n"         // Advance pointer from red to green.
00251         "ld __tmp_reg__, %a0+\n"         // Advance pointer from green to blue.
00252         "ld __tmp_reg__, %a0+\n"         // Read the blue component and leave the pointer on the next color's red.
00253         "rcall send_led_strip_byte%=\n"  // Send blue component.
00254         "rjmp led_strip_asm_end%=\n"     // Jump past the assembly subroutines.
00255 
00256         // send_led_strip_byte subroutine:  Sends a byte to the LED strip.
00257         "send_led_strip_byte%=:\n"
00258         "rcall send_led_strip_bit%=\n"  // Send most-significant bit (bit 7).
00259         "rcall send_led_strip_bit%=\n"
00260         "rcall send_led_strip_bit%=\n"
00261         "rcall send_led_strip_bit%=\n"
00262         "rcall send_led_strip_bit%=\n"
00263         "rcall send_led_strip_bit%=\n"
00264         "rcall send_led_strip_bit%=\n"
00265         "rcall send_led_strip_bit%=\n"  // Send least-significant bit (bit 0).
00266         "ret\n"
00267 
00268         // send_led_strip_bit subroutine:  Sends single bit to the LED strip by driving the data line
00269         // high for some time.  The amount of time the line is high depends on whether the bit is 0 or 1,
00270         // but this function always takes the same time (2 us).
00271         "send_led_strip_bit%=:\n"
00272 #if F_CPU == 8000000
00273         "rol __tmp_reg__\n"                      // Rotate left through carry.
00274 #endif
00275         "sbi %2, %3\n"                           // Drive the line high.
00276 #if F_CPU != 8000000
00277         "rol __tmp_reg__\n"                      // Rotate left through carry.
00278 #endif
00279 
00280 #if F_CPU == 16000000
00281         "nop\n" "nop\n"
00282 #elif F_CPU == 20000000
00283         "nop\n" "nop\n" "nop\n" "nop\n"
00284 #endif
00285 
00286         "brcs .+2\n" "cbi %2, %3\n"              // If the bit to send is 0, drive the line low now.
00287 
00288 #if F_CPU == 8000000
00289         "nop\n" "nop\n"
00290 #elif F_CPU == 16000000
00291         "nop\n" "nop\n" "nop\n" "nop\n" "nop\n"
00292 #elif F_CPU == 20000000
00293         "nop\n" "nop\n" "nop\n" "nop\n" "nop\n"
00294         "nop\n" "nop\n"
00295 #endif
00296 
00297         "brcc .+2\n" "cbi %2, %3\n"              // If the bit to send is 1, drive the line low now.
00298 
00299         "ret\n"
00300         "led_strip_asm_end%=: "
00301         : "=b" (colors)
00302         : "0" (colors),         // %a0 points to the next color to display
00303           "I" (pinAddr[pin]),   // %2 is the port register (e.g. PORTC)
00304           "I" (pinBit[pin])     // %3 is the pin number (0-8)
00305       );
00306 
00307       #elif defined(__arm__)
00308       asm volatile(
00309         "ldrb r12, [%0, #1]\n"    // Load green.
00310         "lsls r12, r12, #24\n"    // Put green in MSB of color register.
00311         "ldrb r3, [%0, #0]\n"     // Load red.
00312         "lsls r3, r3, #16\n"
00313         "orrs r12, r12, r3\n"     // Put red in color register.
00314         "ldrb r3, [%0, #2]\n"     // Load blue.
00315         "lsls r3, r3, #8\n"
00316         "orrs r12, r12, r3\n"     // Put blue in LSB of color register.
00317         "rbit r12, r12\n"         // Reverse the bits so we can use right rotations.
00318         "adds  %0, %0, #3\n"      // Advance pointer to next color.
00319     
00320         "mov r3, #24\n"           // Initialize the loop counter register.
00321 
00322         "send_led_strip_bit%=:\n"
00323         "str %[val], %[set]\n"            // Drive the line high.
00324         "rrxs r12, r12\n"                 // Rotate right through carry.
00325 
00326         "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n"
00327         "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n"
00328         "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n"
00329 
00330         "it cc\n" "strcc %[val], %[clear]\n"  // If the bit to send is 0, set the line low now.
00331 
00332         "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n"
00333         "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n"
00334         "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n"
00335         "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n"
00336 
00337         "it cs\n" "strcs %[val], %[clear]\n"  // If the bit to send is 1, set the line low now.
00338 
00339         "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n"
00340         "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n" "nop\n"
00341 
00342         "sub r3, r3, #1\n"                // Decrement the loop counter.
00343         "cbz r3, led_strip_asm_end%=\n"   // If we have sent 24 bits, go to the end.
00344         "b send_led_strip_bit%=\n"
00345 
00346         "led_strip_asm_end%=:\n"
00347 
00348       : "=r" (colors)
00349       : "0" (colors),
00350         [set] "m" (port->PIO_SODR),
00351         [clear] "m" (port->PIO_CODR),
00352         [val] "r" (pinValue)
00353       : "r3", "r12", "cc"
00354       );
00355 
00356       #endif
00357 
00358       if (PololuLedStripBase::interruptFriendly)
00359       {
00360         // Experimentally on an AVR we found that one NOP is required after the SEI to actually let the
00361         // interrupts fire.
00362         __enable_irq();
00363         asm volatile("nop\n");
00364         __disable_irq();
00365       }
00366     }
00367     __enable_irq();         // Re-enable interrupts now that we are done.
00368     delayMicroseconds(50);  // Hold the line low for 50 microseconds to send the reset signal.
00369   }
00370 
00371 }
00372 
00373 using namespace Pololu;


segbot_led
Author(s): Pato Lankenau , Rolando Fernandez
autogenerated on Thu Jun 6 2019 21:37:07