$search
00001 /* 00002 * BlinkM_funcs.h -- Arduino 'library' to control BlinkM 00003 * -------------- 00004 * 00005 * 00006 * Note: original version of this file lives with the BlinkMTester sketch 00007 * 00008 * Note: all the functions are declared 'static' because 00009 * it saves about 1.5 kbyte in code space in final compiled sketch. 00010 * A C++ library of this costs a 1kB more. 00011 * 00012 * 2007-8, Tod E. Kurt, ThingM, http://thingm.com/ 00013 * 00014 * version: 20081101 00015 * 00016 * history: 00017 * 20080101 - initial release 00018 * 20080203 - added setStartupParam(), bugfix receiveBytes() from Dan Julio 00019 * 20081101 - fixed to work with Arduino-0012, added MaxM commands, 00020 * added test script read/write functions, cleaned up some functions 00021 * 20090121 - added I2C bus scan functions, has dependencies on private 00022 * functions inside Wire library, so might break in the future 00023 * 20100420 - added BlinkM_startPower and _stopPower 00024 * 00025 */ 00026 00027 #include <Wire.h> 00028 00029 extern "C" { 00030 #include "utility/twi.h" // from Wire library, so we can do bus scanning 00031 } 00032 00033 00034 // format of light script lines: duration, command, arg1,arg2,arg3 00035 typedef struct _blinkm_script_line { 00036 uint8_t dur; 00037 uint8_t cmd[4]; // cmd,arg1,arg2,arg3 00038 } blinkm_script_line; 00039 00040 00041 // Call this first (when powering BlinkM from a power supply) 00042 static void BlinkM_begin() 00043 { 00044 Wire.begin(); // join i2c bus (address optional for master) 00045 } 00046 00047 /* 00048 * actually can't do this either, because twi_init() has THREE callocs in it too 00049 * 00050 static void BlinkM_reset() 00051 { 00052 twi_init(); // can't just call Wire.begin() again because of calloc()s there 00053 } 00054 */ 00055 00056 // 00057 // each call to twi_writeTo() should return 0 if device is there 00058 // or other value (usually 2) if nothing is at that address 00059 // 00060 static void BlinkM_scanI2CBus(byte from, byte to, 00061 void(*callback)(byte add, byte result) ) 00062 { 00063 byte rc; 00064 byte data = 0; // not used, just an address to feed to twi_writeTo() 00065 for( byte addr = from; addr <= to; addr++ ) { 00066 rc = twi_writeTo(addr, &data, 0, 1, 1); 00067 callback( addr, rc ); 00068 } 00069 } 00070 00071 // 00072 // 00073 static int8_t BlinkM_findFirstI2CDevice() 00074 { 00075 byte rc; 00076 byte data = 0; // not used, just an address to feed to twi_writeTo() 00077 for( byte addr=1; addr < 120; addr++ ) { // only scan addrs 1-120 00078 rc = twi_writeTo(addr, &data, 0, 1, 1); 00079 if( rc == 0 ) return addr; // found an address 00080 } 00081 return -1; // no device found in range given 00082 } 00083 00084 // FIXME: make this more Arduino-like 00085 static void BlinkM_startPowerWithPins(byte pwrpin, byte gndpin) 00086 { 00087 DDRC |= _BV(pwrpin) | _BV(gndpin); // make outputs 00088 PORTC &=~ _BV(gndpin); 00089 PORTC |= _BV(pwrpin); 00090 } 00091 00092 // FIXME: make this more Arduino-like 00093 static void BlinkM_stopPowerWithPins(byte pwrpin, byte gndpin) 00094 { 00095 DDRC &=~ (_BV(pwrpin) | _BV(gndpin)); 00096 } 00097 00098 // 00099 static void BlinkM_startPower() 00100 { 00101 BlinkM_startPowerWithPins( PORTC3, PORTC2 ); 00102 } 00103 00104 // 00105 static void BlinkM_stopPower() 00106 { 00107 BlinkM_stopPowerWithPins( PORTC3, PORTC2 ); 00108 } 00109 00110 // General version of BlinkM_beginWithPower(). 00111 // Call this first when BlinkM is plugged directly into Arduino 00112 static void BlinkM_beginWithPowerPins(byte pwrpin, byte gndpin) 00113 { 00114 BlinkM_startPowerWithPins(pwrpin,gndpin); 00115 delay(100); // wait for things to stabilize 00116 Wire.begin(); 00117 } 00118 00119 // Call this first when BlinkM is plugged directly into Arduino 00120 // FIXME: make this more Arduino-like 00121 static void BlinkM_beginWithPower() 00122 { 00123 BlinkM_beginWithPowerPins( PORTC3, PORTC2 ); 00124 } 00125 00126 // sends a generic command 00127 static void BlinkM_sendCmd(byte addr, byte* cmd, int cmdlen) 00128 { 00129 Wire.beginTransmission(addr); 00130 for( byte i=0; i<cmdlen; i++) 00131 Wire.write(cmd[i]); 00132 Wire.endTransmission(); 00133 } 00134 00135 // receives generic data 00136 // returns 0 on success, and -1 if no data available 00137 // note: responsiblity of caller to know how many bytes to expect 00138 static int BlinkM_receiveBytes(byte addr, byte* resp, byte len) 00139 { 00140 Wire.requestFrom(addr, len); 00141 if( Wire.available() ) { 00142 for( int i=0; i<len; i++) 00143 resp[i] = Wire.read(); 00144 return 0; 00145 } 00146 return -1; 00147 } 00148 00149 // Sets the I2C address of the BlinkM. 00150 // Uses "general call" broadcast address 00151 static void BlinkM_setAddress(byte newaddress) 00152 { 00153 Wire.beginTransmission(0x00); // general call (broadcast address) 00154 Wire.write('A'); 00155 Wire.write(newaddress); 00156 Wire.write(0xD0); 00157 Wire.write(0x0D); // dood! 00158 Wire.write(newaddress); 00159 Wire.endTransmission(); 00160 delay(50); // just in case 00161 } 00162 00163 00164 // Gets the I2C address of the BlinKM 00165 // Kind of redundant when sent to a specific address 00166 // but uses to verify BlinkM communication 00167 static int BlinkM_getAddress(byte addr) 00168 { 00169 Wire.beginTransmission(addr); 00170 Wire.write('a'); 00171 Wire.endTransmission(); 00172 Wire.requestFrom(addr, (byte)1); // general call 00173 if( Wire.available() ) { 00174 byte b = Wire.read(); 00175 return b; 00176 } 00177 return -1; 00178 } 00179 00180 // Gets the BlinkM firmware version 00181 static int BlinkM_getVersion(byte addr) 00182 { 00183 Wire.beginTransmission(addr); 00184 Wire.write('Z'); 00185 Wire.endTransmission(); 00186 Wire.requestFrom(addr, (byte)2); 00187 if( Wire.available() ) { 00188 byte major_ver = Wire.read(); 00189 byte minor_ver = Wire.read(); 00190 return (major_ver<<8) + minor_ver; 00191 } 00192 return -1; 00193 } 00194 00195 // Demonstrates how to verify you're talking to a BlinkM 00196 // and that you know its address 00197 static int BlinkM_checkAddress(byte addr) 00198 { 00199 //Serial.print("Checking BlinkM address..."); 00200 int b = BlinkM_getAddress(addr); 00201 if( b==-1 ) { 00202 //Serial.println("No response, that's not good"); 00203 return -1; // no response 00204 } 00205 //Serial.print("received addr: 0x"); 00206 //Serial.print(b,HEX); 00207 if( b != addr ) 00208 return 1; // error, addr mismatch 00209 else 00210 return 0; // match, everything okay 00211 } 00212 00213 // Sets the speed of fading between colors. 00214 // Higher numbers means faster fading, 255 == instantaneous fading 00215 static void BlinkM_setFadeSpeed(byte addr, byte fadespeed) 00216 { 00217 Wire.beginTransmission(addr); 00218 Wire.write('f'); 00219 Wire.write(fadespeed); 00220 Wire.endTransmission(); 00221 } 00222 00223 // Sets the light script playback time adjust 00224 // The timeadj argument is signed, and is an additive value to all 00225 // durations in a light script. Set to zero to turn off time adjust. 00226 static void BlinkM_setTimeAdj(byte addr, byte timeadj) 00227 { 00228 Wire.beginTransmission(addr); 00229 Wire.write('t'); 00230 Wire.write(timeadj); 00231 Wire.endTransmission(); 00232 } 00233 00234 // Fades to an RGB color 00235 static void BlinkM_fadeToRGB(byte addr, byte red, byte grn, byte blu) 00236 { 00237 Wire.beginTransmission(addr); 00238 Wire.write('c'); 00239 Wire.write(red); 00240 Wire.write(grn); 00241 Wire.write(blu); 00242 Wire.endTransmission(); 00243 } 00244 00245 // Fades to an HSB color 00246 static void BlinkM_fadeToHSB(byte addr, byte hue, byte saturation, byte brightness) 00247 { 00248 Wire.beginTransmission(addr); 00249 Wire.write('h'); 00250 Wire.write(hue); 00251 Wire.write(saturation); 00252 Wire.write(brightness); 00253 Wire.endTransmission(); 00254 } 00255 00256 // Sets an RGB color immediately 00257 static void BlinkM_setRGB(byte addr, byte red, byte grn, byte blu) 00258 { 00259 Wire.beginTransmission(addr); 00260 Wire.write('n'); 00261 Wire.write(red); 00262 Wire.write(grn); 00263 Wire.write(blu); 00264 Wire.endTransmission(); 00265 } 00266 00267 // Fades to a random RGB color 00268 static void BlinkM_fadeToRandomRGB(byte addr, byte rrnd, byte grnd, byte brnd) 00269 { 00270 Wire.beginTransmission(addr); 00271 Wire.write('C'); 00272 Wire.write(rrnd); 00273 Wire.write(grnd); 00274 Wire.write(brnd); 00275 Wire.endTransmission(); 00276 } 00277 // Fades to a random HSB color 00278 static void BlinkM_fadeToRandomHSB(byte addr, byte hrnd, byte srnd, byte brnd) 00279 { 00280 Wire.beginTransmission(addr); 00281 Wire.write('H'); 00282 Wire.write(hrnd); 00283 Wire.write(srnd); 00284 Wire.write(brnd); 00285 Wire.endTransmission(); 00286 } 00287 00288 // 00289 static void BlinkM_getRGBColor(byte addr, byte* r, byte* g, byte* b) 00290 { 00291 Wire.beginTransmission(addr); 00292 Wire.write('g'); 00293 Wire.endTransmission(); 00294 Wire.requestFrom(addr, (byte)3); 00295 if( Wire.available() ) { 00296 *r = Wire.read(); 00297 *g = Wire.read(); 00298 *b = Wire.read(); 00299 } 00300 } 00301 00302 // 00303 static void BlinkM_playScript(byte addr, byte script_id, byte reps, byte pos) 00304 { 00305 Wire.beginTransmission(addr); 00306 Wire.write('p'); 00307 Wire.write(script_id); 00308 Wire.write(reps); 00309 Wire.write(pos); 00310 Wire.endTransmission(); 00311 } 00312 00313 // 00314 static void BlinkM_stopScript(byte addr) 00315 { 00316 Wire.beginTransmission(addr); 00317 Wire.write('o'); 00318 Wire.endTransmission(); 00319 } 00320 00321 // 00322 static void BlinkM_setScriptLengthReps(byte addr, byte script_id, 00323 byte len, byte reps) 00324 { 00325 Wire.beginTransmission(addr); 00326 Wire.write('L'); 00327 Wire.write(script_id); 00328 Wire.write(len); 00329 Wire.write(reps); 00330 Wire.endTransmission(); 00331 } 00332 00333 // Fill up script_line with data from a script line 00334 // currently only script_id = 0 works (eeprom script) 00335 static void BlinkM_readScriptLine(byte addr, byte script_id, 00336 byte pos, blinkm_script_line* script_line) 00337 { 00338 Wire.beginTransmission(addr); 00339 Wire.write('R'); 00340 Wire.write(script_id); 00341 Wire.write(pos); 00342 Wire.endTransmission(); 00343 Wire.requestFrom(addr, (byte)5); 00344 while( Wire.available() < 5 ) ; // FIXME: wait until we get 7 bytes 00345 script_line->dur = Wire.read(); 00346 script_line->cmd[0] = Wire.read(); 00347 script_line->cmd[1] = Wire.read(); 00348 script_line->cmd[2] = Wire.read(); 00349 script_line->cmd[3] = Wire.read(); 00350 } 00351 00352 // 00353 static void BlinkM_writeScriptLine(byte addr, byte script_id, 00354 byte pos, byte dur, 00355 byte cmd, byte arg1, byte arg2, byte arg3) 00356 { 00357 #ifdef BLINKM_FUNCS_DEBUG 00358 Serial.print("writing line:"); Serial.print(pos,DEC); 00359 Serial.print(" with cmd:"); Serial.print(cmd); 00360 Serial.print(" arg1:"); Serial.println(arg1,HEX); 00361 #endif 00362 Wire.beginTransmission(addr); 00363 Wire.write('W'); 00364 Wire.write(script_id); 00365 Wire.write(pos); 00366 Wire.write(dur); 00367 Wire.write(cmd); 00368 Wire.write(arg1); 00369 Wire.write(arg2); 00370 Wire.write(arg3); 00371 Wire.endTransmission(); 00372 00373 } 00374 00375 // 00376 static void BlinkM_writeScript(byte addr, byte script_id, 00377 byte len, byte reps, 00378 blinkm_script_line* lines) 00379 { 00380 #ifdef BLINKM_FUNCS_DEBUG 00381 Serial.print("writing script to addr:"); Serial.print(addr,DEC); 00382 Serial.print(", script_id:"); Serial.println(script_id,DEC); 00383 #endif 00384 for(byte i=0; i < len; i++) { 00385 blinkm_script_line l = lines[i]; 00386 BlinkM_writeScriptLine( addr, script_id, i, l.dur, 00387 l.cmd[0], l.cmd[1], l.cmd[2], l.cmd[3]); 00388 delay(20); // must wait for EEPROM to be programmed 00389 } 00390 BlinkM_setScriptLengthReps(addr, script_id, len, reps); 00391 } 00392 00393 // 00394 static void BlinkM_setStartupParams(byte addr, byte mode, byte script_id, 00395 byte reps, byte fadespeed, byte timeadj) 00396 { 00397 Wire.beginTransmission(addr); 00398 Wire.write('B'); 00399 Wire.write(mode); // default 0x01 == Play script 00400 Wire.write(script_id); // default 0x00 == script #0 00401 Wire.write(reps); // default 0x00 == repeat infinitely 00402 Wire.write(fadespeed); // default 0x08 == usually overridden by sketch 00403 Wire.write(timeadj); // default 0x00 == sometimes overridden by sketch 00404 Wire.endTransmission(); 00405 } 00406 00407 00408 // Gets digital inputs of the BlinkM 00409 // returns -1 on failure 00410 static int BlinkM_getInputsO(byte addr) 00411 { 00412 Wire.beginTransmission(addr); 00413 Wire.write('i'); 00414 Wire.endTransmission(); 00415 Wire.requestFrom(addr, (byte)1); 00416 if( Wire.available() ) { 00417 byte b = Wire.read(); 00418 return b; 00419 } 00420 return -1; 00421 } 00422 00423 // Gets digital inputs of the BlinkM 00424 // stores them in passed in array 00425 // returns -1 on failure 00426 static int BlinkM_getInputs(byte addr, byte inputs[]) 00427 { 00428 Wire.beginTransmission(addr); 00429 Wire.write('i'); 00430 Wire.endTransmission(); 00431 Wire.requestFrom(addr, (byte)4); 00432 while( Wire.available() < 4 ) ; // FIXME: wait until we get 4 bytes 00433 00434 inputs[0] = Wire.read(); 00435 inputs[1] = Wire.read(); 00436 inputs[2] = Wire.read(); 00437 inputs[3] = Wire.read(); 00438 00439 return 0; 00440 }