Welcome to mirror list, hosted at ThFree Co, Russian Federation.

SX1509.cpp « DuetNG « src - github.com/Duet3D/RepRapFirmware.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
blob: 98035ccafa57caa77aeb3556dc7034708c861b32 (plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
/******************************************************************************
SparkFunSX1509.cpp
SparkFun SX1509 I/O Expander Library Source File
Adapted from Sparkfun SX1509 library by dc42, see header below.
******************************************************************************/

/******************************************************************************
Jim Lindblom @ SparkFun Electronics
Original Creation Date: September 21, 2015
https://github.com/sparkfun/SparkFun_SX1509_Arduino_Library

Here you'll find the Arduino code used to interface with the SX1509 I2C
16 I/O expander. There are functions to take advantage of everything the
SX1509 provides - input/output setting, writing pins high/low, reading 
the input value of pins, LED driver utilities (blink, breath, pwm), and
keypad engine utilites.

This code is beerware; if you see me (or any other SparkFun employee) at the
local, and you've found our code helpful, please buy us a round!

Distributed as-is; no warranty is given.
******************************************************************************/

#include "Core.h"
#include "Wire.h"
#include "SX1509.h"
#include "SX1509Registers.h"

SX1509::SX1509()
{
	_clkX = 0;
}

uint8_t SX1509::begin(uint8_t address)
{
	// Store the received parameters into member variables
	deviceAddress =  address;
	
	// Begin I2C
	Wire.begin();

	reset();

	// Communication test. We'll read from two registers with different
	// default values to verify communication.
	unsigned int testRegisters = 0;
	testRegisters = readWord(REG_INTERRUPT_MASK_A);	// this should return 0xFF00

	// Then read a byte that should be 0x00
	if (testRegisters == 0xFF00)
	{
		clock(DefaultOscDivider);
		writeWord(REG_HIGH_INPUT_B, 0xFFFF);		// set all inputs to be 5V-tolerant
		return 1;
	}

	return 0;
}

void SX1509::reset()
{
	// Software reset command sequence:
	writeByte(REG_RESET, 0x12);
	writeByte(REG_RESET, 0x34);
}

void SX1509::setBitsInWord(uint8_t registerAddress, uint16_t bits)
{
	const uint16_t regVal = readWord(registerAddress);
	writeWord(registerAddress, regVal | bits);
}

void SX1509::clearBitsInWord(uint8_t registerAddress, uint16_t bits)
{
	const uint16_t regVal = readWord(registerAddress);
	writeWord(registerAddress, regVal & (~bits));

}

void SX1509::pinMode(uint8_t pin, PinMode inOut)
{
	pinModeMultiple(1u << pin, inOut);
}

void SX1509::pinModeMultiple(uint16_t pins, PinMode inOut)
{
	switch (inOut)
	{
	case INPUT:
		clearBitsInWord(REG_LED_DRIVER_ENABLE_B, pins);
		clearBitsInWord(REG_INPUT_DISABLE_B, pins);
		setBitsInWord(REG_DIR_B, pins);
		clearBitsInWord(REG_PULL_UP_B, pins);
		clearBitsInWord(REG_PULL_DOWN_B, pins);
		break;

	case INPUT_PULLUP:
		clearBitsInWord(REG_LED_DRIVER_ENABLE_B, pins);
		clearBitsInWord(REG_INPUT_DISABLE_B, pins);
		setBitsInWord(REG_DIR_B, pins);
		clearBitsInWord(REG_PULL_DOWN_B, pins);
		setBitsInWord(REG_PULL_UP_B, pins);
		break;

	case INPUT_PULLDOWN:
		clearBitsInWord(REG_LED_DRIVER_ENABLE_B, pins);
		clearBitsInWord(REG_INPUT_DISABLE_B, pins);
		setBitsInWord(REG_DIR_B, pins);
		clearBitsInWord(REG_PULL_UP_B, pins);
		setBitsInWord(REG_PULL_DOWN_B, pins);
		break;

	case OUTPUT_LOW:
		clearBitsInWord(REG_LED_DRIVER_ENABLE_B, pins);
		clearBitsInWord(REG_PULL_UP_B, pins);
		clearBitsInWord(REG_PULL_DOWN_B, pins);
		clearBitsInWord(REG_DATA_B, pins);
		clearBitsInWord(REG_OPEN_DRAIN_B, pins);
		clearBitsInWord(REG_DIR_B, pins);
		break;

	case OUTPUT_HIGH:
		clearBitsInWord(REG_LED_DRIVER_ENABLE_B, pins);
		clearBitsInWord(REG_PULL_UP_B, pins);
		clearBitsInWord(REG_PULL_DOWN_B, pins);
		setBitsInWord(REG_DATA_B, pins);
		clearBitsInWord(REG_OPEN_DRAIN_B, pins);
		clearBitsInWord(REG_DIR_B, pins);
		break;

	case OUTPUT_LOW_OPEN_DRAIN:
		clearBitsInWord(REG_LED_DRIVER_ENABLE_B, pins);
		clearBitsInWord(REG_PULL_UP_B, pins);
		clearBitsInWord(REG_PULL_DOWN_B, pins);
		clearBitsInWord(REG_DATA_B, pins);
		setBitsInWord(REG_OPEN_DRAIN_B, pins);
		clearBitsInWord(REG_DIR_B, pins);
		break;

	case OUTPUT_HIGH_OPEN_DRAIN:
		clearBitsInWord(REG_LED_DRIVER_ENABLE_B, pins);
		clearBitsInWord(REG_PULL_UP_B, pins);
		clearBitsInWord(REG_PULL_DOWN_B, pins);
		setBitsInWord(REG_DATA_B, pins);
		setBitsInWord(REG_OPEN_DRAIN_B, pins);
		clearBitsInWord(REG_DIR_B, pins);
		break;

	case OUTPUT_PWM:
		ledDriverInitMultiple(pins, false, false);
		break;

	case OUTPUT_PWM_OPEN_DRAIN:
		ledDriverInitMultiple(pins, false, true);
		break;

	default:
		break;
	}
}

void SX1509::digitalWrite(uint8_t pin, bool highLow)
{
	if (highLow)
	{
		setBitsInWord(REG_DATA_B, 1u << pin);
	}
	else
	{
		clearBitsInWord(REG_DATA_B, 1u << pin);
	}
}

bool SX1509::digitalRead(uint8_t pin)
{
	if (pin >= 8)
	{
		return (readByte(REG_DATA_B) & (1u << (pin - 8))) != 0;
	}
	else
	{
		return (readByte(REG_DATA_A) & (1u << pin)) != 0;
	}
}

uint16_t SX1509::digitalReadAll()
{
	return readWord(REG_DATA_B);
}

void SX1509::ledDriverInit(uint8_t pin, bool log, bool openDrain)
{
	ledDriverInitMultiple(1u << pin, log, openDrain);
}

void SX1509::ledDriverInitMultiple(uint16_t pins, bool log, bool openDrain)
{
	if (openDrain)
	{
		setBitsInWord(REG_OPEN_DRAIN_B, pins);
	}
	else
	{
		clearBitsInWord(REG_OPEN_DRAIN_B, pins);
	}
	setBitsInWord(REG_INPUT_DISABLE_B, pins);	// disable input buffer
	clearBitsInWord(REG_PULL_UP_B, pins);		// disable pullup
	clearBitsInWord(REG_PULL_DOWN_B, pins);		// disable pulldown
	clearBitsInWord(REG_DIR_B, pins);			// set as an output
	

	// Configure LED driver clock and mode (REG_MISC)
	uint8_t tempByte = readByte(REG_MISC);
	if (log)
	{
		tempByte |= (1u << 7) | (1u << 3);		// set logarithmic mode bank B and A
	}
	else
	{
		tempByte &= ~((1u << 7) | (1u << 3));	// set linear mode bank B and A
	}
	writeByte(REG_MISC, tempByte);
	
	// Enable LED driver operation (REG_LED_DRIVER_ENABLE)
	setBitsInWord(REG_LED_DRIVER_ENABLE_B, pins);
	
	// Set REG_DATA bit low ~ LED driver started
	clearBitsInWord(REG_DATA_B, pins);
}

void SX1509::analogWrite(uint8_t pin, uint8_t iOn)
{
	// Write the on intensity of pin
	// Linear mode: Ion = iOn
	// Log mode: Ion = f(iOn)
	// We use the pins as active-high outputs to drive the fan mosfets, not to sink LED current directly.
	// This means that we need to invert the intensity, and log mode doesn't make sense.
	writeByte(REG_I_ON[pin], ~iOn);
}

void SX1509::blink(uint8_t pin, unsigned long tOn, unsigned long tOff, uint8_t onIntensity, uint8_t offIntensity)
{
	const uint8_t onReg = calculateLEDTRegister(tOn);
	const uint8_t offReg = calculateLEDTRegister(tOff);
	
	setupBlink(pin, onReg, offReg, onIntensity, offIntensity, 0, 0, false, false);
}

void SX1509::breathe(uint8_t pin, unsigned long tOn, unsigned long tOff, unsigned long rise, unsigned long fall, uint8_t onInt, uint8_t offInt, bool log, bool openDrain)
{
	offInt = constrain<uint8_t>(offInt, 0, 7);
	
	const uint8_t onReg = calculateLEDTRegister(tOn);
	const uint8_t offReg = calculateLEDTRegister(tOff);
	
	const uint8_t riseTime = calculateSlopeRegister(rise, onInt, offInt);
	const uint8_t fallTime = calculateSlopeRegister(fall, onInt, offInt);
	
	setupBlink(pin, onReg, offReg, onInt, offInt, riseTime, fallTime, log, openDrain);
}

void SX1509::setupBlink(uint8_t pin, uint8_t tOn, uint8_t tOff, uint8_t onIntensity, uint8_t offIntensity, uint8_t tRise, uint8_t tFall, bool log, bool openDrain)
{
	ledDriverInit(pin, log, openDrain);
	
	// Keep parameters within their limits:
	tOn &= 0x1F;	// tOn should be a 5-bit value
	tOff &= 0x1F;	// tOff should be a 5-bit value
	offIntensity &= 0x07;
	// Write the time on
	// 1-15:  TON = 64 * tOn * (255/ClkX)
	// 16-31: TON = 512 * tOn * (255/ClkX)
	writeByte(REG_T_ON[pin], tOn);
	
	// Write the time/intensity off register
	// 1-15:  TOFF = 64 * tOff * (255/ClkX)
	// 16-31: TOFF = 512 * tOff * (255/ClkX)
	// linear Mode - IOff = 4 * offIntensity
	// log mode - Ioff = f(4 * offIntensity)
	writeByte(REG_OFF[pin], (tOff << 3) | offIntensity);
	
	// Write the on intensity:
	writeByte(REG_I_ON[pin], onIntensity);
	
	// Prepare tRise and tFall
	tRise &= 0x1F;	// tRise is a 5-bit value
	tFall &= 0x1F;	// tFall is a 5-bit value
	
	// Write regTRise
	// 0: Off
	// 1-15:  TRise =      (regIOn - (4 * offIntensity)) * tRise * (255/ClkX)
	// 16-31: TRise = 16 * (regIOn - (4 * offIntensity)) * tRise * (255/ClkX)
	if (REG_T_RISE[pin] != 0xFF)
	{
		writeByte(REG_T_RISE[pin], tRise);
	}

	// Write regTFall
	// 0: off
	// 1-15:  TFall =      (regIOn - (4 * offIntensity)) * tFall * (255/ClkX)
	// 16-31: TFall = 16 * (regIOn - (4 * offIntensity)) * tFall * (255/ClkX)
	if (REG_T_FALL[pin] != 0xFF)
	{
		writeByte(REG_T_FALL[pin], tFall);
	}
}

void SX1509::keypad(uint8_t rows, uint8_t columns, unsigned int sleepTime, uint8_t scanTime, uint8_t debounceTime)
{
	// Set regDir 0:7 outputs, 8:15 inputs:
	uint16_t tempWord = readWord(REG_DIR_B);
	for (uint8_t i = 0; i<rows; i++)
	{
		tempWord &= ~(1 << i);
	}
	for (uint8_t i = 8; i < (columns * 2); i++)
	{
		tempWord |= (1u << i);
	}
	writeWord(REG_DIR_B, tempWord);
	
	// Set regOpenDrain on 0:7:
	uint8_t tempByte = readByte(REG_OPEN_DRAIN_A);
	for (uint8_t i = 0; i < rows; i++)
	{
		tempByte |= (1u << i);
	}
	writeByte(REG_OPEN_DRAIN_A, tempByte);
	
	// Set regPullUp on 8:15:
	tempByte = readByte(REG_PULL_UP_B);
	for (uint8_t i=0; i < columns; i++)
	{
		tempByte |= (1u << i);
	}
	writeByte(REG_PULL_UP_B, tempByte);
	
	// Debounce Time must be less than scan time
	debounceTime = constrain<uint8_t>(debounceTime, 1, 64);
	scanTime = constrain<uint8_t>(scanTime, 1, 128);
	if (debounceTime >= scanTime)
	{
		debounceTime = scanTime >> 1; // Force debounceTime to be less than scanTime
	}
	debounceKeypad(debounceTime, rows, columns);
	
	// Calculate scanTimeBits, based on scanTime
	uint8_t scanTimeBits = 0;
	for (uint8_t i = 7; i > 0; i--)
	{
		if ((scanTime & (1u << i)) != 0)
		{
			scanTimeBits = i;
			break;
		}
	}
	
	// Calculate sleepTimeBits, based on sleepTime
	uint8_t sleepTimeBits = 0;
	if (sleepTime != 0)
	{
		for (uint8_t i = 7; i != 0; i--)
		{
			if ((sleepTime & (1u << (i + 6))) != 0)
			{
				sleepTimeBits = i;
				break;
			}
		}
		// If sleepTime was non-zero, but less than 128, 
		// assume we wanted to turn sleep on, set it to minimum:
		if (sleepTimeBits == 0)
		{
			sleepTimeBits = 1;
		}
	}
	
	// RegKeyConfig1 sets the auto sleep time and scan time per row
	sleepTimeBits = (sleepTimeBits & 0b111)<<4;	
	scanTimeBits &= 0b111;	// Scan time is bits 2:0
	tempByte = sleepTime | scanTimeBits;
	writeByte(REG_KEY_CONFIG_1, tempByte);
	
	// RegKeyConfig2 tells the SX1509 how many rows and columns we've got going
	rows = (rows - 1) & 0b111;	// 0 = off, 0b001 = 2 rows, 0b111 = 8 rows, etc.
	columns = (columns - 1) & 0b111;	// 0b000 = 1 column, ob111 = 8 columns, etc.
	writeByte(REG_KEY_CONFIG_2, (rows << 3) | columns);
}

uint16_t SX1509::readKeypad()
{
	return ~readWord(REG_KEY_DATA_1);
}

uint8_t SX1509::getRow(uint16_t keyData)
{
	const uint8_t rowData = uint8_t(keyData & 0x00FF);
	
	for (uint8_t i = 0; i < 8; i++)
	{
		if (rowData & (1u << i))
		{
			return i;
		}
	}
	return 0;
}

uint8_t SX1509::getCol(uint16_t keyData)
{
	const uint8_t colData = uint8_t((keyData & 0xFF00) >> 8);
	
	for (uint8_t i = 0; i < 8; i++)
	{
		if (colData & (1u << i))
		{
			return i;
		}
	}
	return 0;
	
}

void SX1509::debounceConfig(uint8_t configValue)
{
	// First make sure clock is configured
	uint8_t tempByte = readByte(REG_MISC);
	if ((tempByte & 0x70) == 0)
	{
		tempByte |= (1<<4);	// Just default to no divider if not set
		writeByte(REG_MISC, tempByte);
	}
	tempByte = readByte(REG_CLOCK);
	if ((tempByte & 0x60) == 0)
	{
		tempByte |= (1<<6);	// default to internal osc.
		writeByte(REG_CLOCK, tempByte);
	}
	
	configValue &= 0b111;	// 3-bit value
	writeByte(REG_DEBOUNCE_CONFIG, configValue);
}

void SX1509::debounceTime(uint8_t time)
{
	// Debounce time-to-uint8_t map: (assuming fOsc = 2MHz)
	// 0: 0.5ms		1: 1ms
	// 2: 2ms		3: 4ms
	// 4: 8ms		5: 16ms
	// 6: 32ms		7: 64ms
	// 2^(n-1)
	uint8_t configValue = 0;
	// We'll check for the highest set bit position, 
	// and use that for debounceConfig
	for (int i = 7; i >= 0; i--)
	{
		if ((time & (1u << i)) != 0)
		{
			configValue = i + 1;
			break;
		}
	}
	configValue = constrain<uint8_t>(configValue, 0, 7);
	
	debounceConfig(configValue);
}

void SX1509::debouncePin(uint8_t pin)
{
	unsigned int debounceEnable = readWord(REG_DEBOUNCE_ENABLE_B);
	debounceEnable |= (1<<pin);
	writeWord(REG_DEBOUNCE_ENABLE_B, debounceEnable);
}

void SX1509::debounceKeypad(uint8_t time, uint8_t numRows, uint8_t numCols)
{
	// Set up debounce time:
	debounceTime(time);
	
	// Set up debounce pins:
	for (uint8_t i = 0; i < numRows; i++)
	{
		debouncePin(i);
	}
	for (uint8_t i = 0; i < (8 + numCols); i++)
	{
		debouncePin(i);
	}
}

void SX1509::enableInterrupt(uint8_t pin, uint8_t riseFall)
{
	enableInterruptMultiple(1u << pin, riseFall);
}

void SX1509::enableInterruptMultiple(uint16_t pins, uint8_t riseFall)
{
	// Set REG_SENSE_XXX
	// Sensitivity is set as follows:
	// 00: None
	// 01: Rising
	// 10: Falling
	// 11: Both
	uint8_t sensitivity;
	switch (riseFall)
	{
	case CHANGE:
		sensitivity = 0b11;
		break;
	case FALLING:
		sensitivity = 0b10;
		break;
	case RISING:
		sensitivity = 0b01;
		break;
	default:
		sensitivity = 0;
	}

	uint32_t pinMask = readDword(REG_SENSE_HIGH_B);
	for (unsigned int i = 0; i < 16; ++i)
	{
		if ((pins & (1 << i)) != 0)
		{
			pinMask &= ~(0x03 << (2 * i));
			pinMask |= (sensitivity << (2 * i));
		}
	}

	writeDword(REG_SENSE_HIGH_B, pinMask);

	clearBitsInWord(REG_INTERRUPT_MASK_B, pins);
}

uint16_t SX1509::interruptSource(bool clear)
{
	const uint16_t intSource = readWord(REG_INTERRUPT_SOURCE_B);
	if (clear)
	{
		writeWord(REG_INTERRUPT_SOURCE_B, 0xFFFF);	// Clear interrupts
	}
	return intSource;
}

bool SX1509::checkInterrupt(uint8_t pin)
{
	return (interruptSource(false) & (1u << pin)) != 0;
}

void SX1509::clock(uint8_t oscDivider)
{
	// RegClock constructed as follows:
	//	6:5 - Oscillator frequency source
	//		00: off, 01: external input, 10: internal 2MHz, 1: reserved
	//	4 - OSCIO pin function
	//		0: input, 1 output
	//	3:0 - Frequency of oscout pin
	//		0: LOW, 0xF: high, else fOSCOUT = FoSC/(2^(RegClock[3:0]-1))
	writeByte(REG_CLOCK, (2u << 5) | (1u << 4) | (1u << 0));	// internal 2MHz oscillator, OSCIO outputs at that frequency
	
	// Config RegMisc[6:4] with oscDivider
	// 0: off, else ClkX = fOSC / (2^(RegMisc[6:4] - 1))
	oscDivider = constrain<uint8_t>(oscDivider, 1, 7);
	_clkX = 2000000.0 / (1u << (oscDivider - 1u));			// update private clock variable
	uint8_t regMisc = readByte(REG_MISC);
	regMisc &= ~((0b111 << 4) | (1u << 1) | (1u << 0));		// clear clock divider bits, auto-increment is enabled, clear interrupt on register read
	regMisc |= oscDivider << 4;
	writeByte(REG_MISC, regMisc);
}

uint8_t SX1509::calculateLEDTRegister(int ms)
{
	if (_clkX == 0)
	{
		return 0;
	}
	
	int regOn1 = (int)(((float)ms / 1000.0) / (64.0 * 255.0 / (float) _clkX));
	int regOn2 = regOn1 / 8;
	regOn1 = constrain<int>(regOn1, 1, 15);
	regOn2 = constrain<int>(regOn2, 16, 31);
	
	const float timeOn1 = 64.0 * regOn1 * 255.0 / _clkX * 1000.0;
	const float timeOn2 = 512.0 * regOn2 * 255.0 / _clkX * 1000.0;

	return (abs(timeOn1 - ms) < abs(timeOn2 - ms)) ? regOn1 : regOn2;
}

uint8_t SX1509::calculateSlopeRegister(int ms, uint8_t onIntensity, uint8_t offIntensity)
{
	if (_clkX == 0)
	{
		return 0;
	}
	
	const float tFactor = ((float) onIntensity - (4.0 * (float)offIntensity)) * 255.0 / (float) _clkX;
	const float timeS = float(ms) / 1000.0;
	
	int regSlope1 = timeS / tFactor;
	int regSlope2 = regSlope1 / 16;
	
	regSlope1 = constrain<int>(regSlope1, 1, 15);
	regSlope2 = constrain<int>(regSlope2, 16, 31);

	const float regTime1 = regSlope1 * tFactor * 1000.0;
	const float regTime2 = 16 * regTime1;

	return (abs(regTime1 - ms) < abs(regTime2 - ms)) ? regSlope1 : regSlope2;
}

// readByte(uint8_t registerAddress)
//	This function reads a single uint8_t located at the registerAddress register.
//	- deviceAddress should already be set by the constructor.
//	- Return value is the uint8_t read from registerAddress
//		- Currently returns 0 if communication has timed out
uint8_t SX1509::readByte(uint8_t registerAddress)
{
	unsigned int timeout = ReceiveTimeout;

	Wire.beginTransmission(deviceAddress);
	Wire.write(registerAddress);
	Wire.endTransmission();
	Wire.requestFrom(deviceAddress, (uint8_t) 1);

	while ((Wire.available() < 1) && (timeout != 0))
	{
		timeout--;
	}
		
	if (timeout == 0)
	{
		return 0;
	}

	return Wire.read();
}

// readWord(uint8_t registerAddress)
//	This function will read a two-uint8_t word beginning at registerAddress
//	- A 16-bit unsigned int will be returned.
//		- The msb of the return value will contain the value read from registerAddress
//		- The lsb of the return value will contain the value read from registerAddress + 1
uint16_t SX1509::readWord(uint8_t registerAddress)
{
	unsigned int timeout = ReceiveTimeout * 2;

	Wire.beginTransmission(deviceAddress);
	Wire.write(registerAddress);
	Wire.endTransmission();
	Wire.requestFrom(deviceAddress, (uint8_t) 2);

	while ((Wire.available() < 2) && (timeout != 0))
	{
		timeout--;
	}
		
	if (timeout == 0)
	{
		return 0;
	}
	
	uint16_t msb = (Wire.read() & 0x00FF) << 8;
	uint16_t lsb = (Wire.read() & 0x00FF);
	return msb | lsb;
}

// readDword(uint8_t registerAddress)
//	This function will read a two-uint8_t word beginning at registerAddress
//	- A 32-bit unsigned int will be returned.
//		- The msb of the return value will contain the value read from registerAddress
//		- The lsb of the return value will contain the value read from registerAddress + 1
uint32_t SX1509::readDword(uint8_t registerAddress)
{
	unsigned int timeout = ReceiveTimeout * 2;

	Wire.beginTransmission(deviceAddress);
	Wire.write(registerAddress);
	Wire.endTransmission();
	Wire.requestFrom(deviceAddress, (uint8_t) 4);

	while ((Wire.available() < 4) && (timeout != 0))
	{
		timeout--;
	}

	if (timeout == 0)
	{
		return 0;
	}

	uint32_t rslt = Wire.read() & 0x00FF;
	rslt <<= 8;
	rslt |= (Wire.read() & 0x00FF);
	rslt <<= 8;
	rslt |= (Wire.read() & 0x00FF);
	rslt <<= 8;
	rslt |= (Wire.read() & 0x00FF);
	return rslt;
}

// readBytes(uint8_t firstRegisterAddress, uint8_t * destination, uint8_t length)
//	This function reads a series of bytes incrementing from a given address
//	- firstRegsiterAddress is the first address to be read
//	- destination is an array of bytes where the read values will be stored into
//	- length is the number of bytes to be read
//	- No return value.
void SX1509::readBytes(uint8_t firstRegisterAddress, uint8_t * destination, uint8_t length)
{
	Wire.beginTransmission(deviceAddress);
	Wire.write(firstRegisterAddress);
	Wire.endTransmission();
	Wire.requestFrom(deviceAddress, length);
	
	while (Wire.available() < length) { }
	
	for (uint8_t i = 0; i < length; i++)
	{
		destination[i] = Wire.read();
	}
}

// writeByte(uint8_t registerAddress, uint8_t writeValue)
//	This function writes a single uint8_t to a single register on the SX509.
//	- writeValue is written to registerAddress
//	- deviceAddres should already be set from the constructor
//	- No return value.
void SX1509::writeByte(uint8_t registerAddress, uint8_t writeValue)
{
	Wire.beginTransmission(deviceAddress);
	Wire.write(registerAddress);
	Wire.write(writeValue);
	Wire.endTransmission();
}

// writeWord(uint8_t registerAddress, uint16_t writeValue)
//	This function writes a two-uint8_t word to registerAddress and registerAddress + 1
//	- the upper uint8_t of writeValue is written to registerAddress
//		- the lower uint8_t of writeValue is written to registerAddress + 1
//	- No return value.
void SX1509::writeWord(uint8_t registerAddress, uint16_t writeValue)
{
	Wire.beginTransmission(deviceAddress);
	Wire.write(registerAddress);
	Wire.write((uint8_t)(writeValue >> 8));
	Wire.write((uint8_t)writeValue);
	Wire.endTransmission();
}

// writeDword(uint8_t registerAddress, uint32_t writeValue)
//	This function writes a four-uint8_t word to registerAddress .. registerAddress + 3, msb first
//	- No return value.
void SX1509::writeDword(uint8_t registerAddress, uint32_t writeValue)
{
	Wire.beginTransmission(deviceAddress);
	Wire.write(registerAddress);
	Wire.write((uint8_t)(writeValue >> 24));
	Wire.write((uint8_t)(writeValue >> 16));
	Wire.write((uint8_t)(writeValue >> 8));
	Wire.write((uint8_t)writeValue);
	Wire.endTransmission();	
}

// writeBytes(uint8_t firstRegisterAddress, uint8_t * writeArray, uint8_t length)
//	This function writes an array of bytes, beginning at a specific address
//	- firstRegisterAddress is the initial register to be written.
//		- All writes following will be at incremental register addresses.
//	- writeArray should be an array of uint8_t values to be written.
//	- length should be the number of bytes to be written.
//	- no return value.
void SX1509::writeBytes(uint8_t firstRegisterAddress, uint8_t * writeArray, uint8_t length)
{
	Wire.beginTransmission(deviceAddress);
	Wire.write(firstRegisterAddress);
	for (uint8_t i=0; i < length; i++)
	{
		Wire.write(writeArray[i]);
	}
	Wire.endTransmission();
}

// End