Created
          September 23, 2015 22:17 
        
      - 
      
- 
        Save antimodular/3c8f27272bc7522b4f52 to your computer and use it in GitHub Desktop. 
  
    
      This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
      Learn more about bidirectional Unicode characters
    
  
  
    
  | /* ============================================================================= | |
| LIDAR-Lite v2: Change the I2C address of multiple sensors with PWR_EN line | |
| This example demonstrates how to chage the i2c address of multiple sensors. | |
| The library is in BETA, so subscribe to the github repo to recieve updates, or | |
| just check in periodically: | |
| https://github.com/PulsedLight3D/LIDARLite_v2_Arduino_Library | |
| To learn more read over lidarlite.cpp as each function is commented | |
| =========================================================================== */ | |
| #include <Wire.h> | |
| //#include <LIDARLite.h> | |
| #define DELAY_USEC 50 | |
| #define RegisterMeasure 0x00 // Register to write to initiate ranging. | |
| #define MeasureValue 0x04 // Value to initiate ranging. | |
| #define RegisterHighLowB 0x8f // Register to get both High and Low bytes in 1 call. | |
| int reading = 0; | |
| int readings[] = {0, 0}; | |
| long dT; // difference in time between readings | |
| long tNew, tOld; // time in milliseconds() | |
| int currentPin; | |
| int sensorPins[] = {2, A3}; // Array of pins connected to the sensor Power Enable lines | |
| //unsigned char addresses[] = {0x62, 0x62}; | |
| unsigned char addresses[] = {0x66, 0x68}; | |
| unsigned char addresses_default = 0x62; | |
| int ledPin = 13; | |
| //LIDARLite myLidarLite; | |
| unsigned long resetLatency = 0; | |
| unsigned long resetTimer; | |
| unsigned long last_rest[2]; | |
| int resetCnt = 0; | |
| bool nackA[] = {false,false}; | |
| //------ | |
| boolean errorReporting; | |
| void setup() | |
| { | |
| Wire.begin(); // basic I2C library | |
| Serial.begin(9600); // start serial communication at 9600bps | |
| while (!Serial) ; | |
| delay(10); | |
| Serial.println("LIDAR Test_7"); | |
| tOld = millis(); | |
| currentPin = 0; | |
| // digitalWrite(sensorPins[0], LOW); | |
| // digitalWrite(sensorPins[1], LOW); | |
| LIDARLite_begin(0, false, false, addresses_default); | |
| LIDARLite_changeAddressMultiPwrEn(2, sensorPins, addresses, false); | |
| /* | |
| pinMode(sensorPins[0], OUTPUT); | |
| delay(2); | |
| digitalWrite(sensorPins[0], HIGH); | |
| delay(20); | |
| //LIDARLite_configure | |
| pinMode(sensorPins[1], OUTPUT); | |
| delay(2); | |
| digitalWrite(sensorPins[1], HIGH); | |
| delay(20); | |
| */ | |
| pinMode(ledPin, OUTPUT); | |
| resetTimer = millis(); | |
| last_rest[0] = millis(); | |
| last_rest[1] = millis(); | |
| } | |
| void resetSensors(int i) { | |
| if (millis() - last_rest[i] > 3000 ) { | |
| Serial.print("resetSensors "); | |
| Serial.print(i); | |
| Serial.println(); | |
| digitalWrite(sensorPins[i], LOW); | |
| delay(100); | |
| LIDARLite_begin(0, false, false, addresses_default); | |
| // LIDARLite_changeAddressMultiPwrEn(2, sensorPins, addresses, false); | |
| pinMode(sensorPins[i], OUTPUT); // Pin to first LIDAR-Lite Power Enable line | |
| delay(2); | |
| digitalWrite(sensorPins[i], HIGH); | |
| delay(20); | |
| LIDARLite_configure(1, addresses_default); | |
| LIDARLite_changeAddress(addresses[i], true, addresses_default); // We have to turn off the party line to actually get these to load | |
| resetLatency = millis() - resetTimer; | |
| resetTimer = millis(); | |
| last_rest[i] = millis(); | |
| resetCnt++; | |
| } else { | |
| Serial.print("wait before calling resetSensors again "); | |
| Serial.print(i); | |
| Serial.print(" "); | |
| Serial.print(millis() - last_rest[i]); | |
| Serial.println(); | |
| } | |
| } | |
| void loop() | |
| { | |
| Wire.beginTransmission(addresses[currentPin]); // transmit to LIDAR-Lite | |
| Wire.write(RegisterMeasure); | |
| Wire.write(MeasureValue); | |
| int nackCatcher = Wire.endTransmission(); | |
| if (nackCatcher != 0) { | |
| Serial.println("\t\tA > nack A"); | |
| nackA[currentPin] = true; | |
| resetSensors(currentPin); | |
| } | |
| else { | |
| nackA[currentPin] = false; | |
| delayMicroseconds(DELAY_USEC); | |
| Wire.beginTransmission((int)addresses[currentPin]); // transmit to LIDAR-Lite | |
| Wire.write((int)RegisterHighLowB); // sets register pointer to (0x8f) | |
| nackCatcher = Wire.endTransmission(); | |
| if (nackCatcher != 0) { | |
| Serial.println("\t\tB > nack B"); | |
| resetSensors(currentPin); | |
| } else { | |
| delayMicroseconds(DELAY_USEC); | |
| nackCatcher = Wire.requestFrom((int)addresses[currentPin], 2); | |
| if (nackCatcher == 0) { | |
| Serial.println("\t\t8 > nack 8"); | |
| } | |
| delayMicroseconds(DELAY_USEC); | |
| if (Wire.available() >= 2) { // if two bytes were received | |
| reading = Wire.read() * 256; | |
| reading |= Wire.read(); | |
| readings[currentPin] = reading; | |
| if(reading < 100) digitalWrite(ledPin, HIGH); | |
| else digitalWrite(ledPin, LOW); | |
| } | |
| }//else B | |
| }//else A | |
| delay(10); | |
| currentPin++; | |
| if (currentPin > 1) { | |
| currentPin = 0; | |
| Serial.print(readings[0]); | |
| Serial.print("\t , "); | |
| Serial.print(readings[1]); | |
| Serial.print("\t , "); | |
| Serial.print(resetCnt); | |
| Serial.print("\t , "); | |
| Serial.print(resetLatency); | |
| Serial.println(); | |
| } | |
| } | |
  
    
      This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
      Learn more about bidirectional Unicode characters
    
  
  
    
  | void LIDARLite_begin(int configuration, bool fasti2c, bool showErrorReporting, char LidarLiteI2cAddress) { | |
| errorReporting = showErrorReporting; | |
| Wire.begin(); // Start I2C | |
| if (fasti2c) { | |
| //#if ARDUINO >= 157 | |
| Wire.setClock(400000UL); // Set I2C frequency to 400kHz, for the Due | |
| //#else | |
| // TWBR = ((F_CPU / 400000UL) - 16) / 2; // Set I2C frequency to 400kHz | |
| //#endif | |
| } | |
| LIDARLite_configure(configuration, LidarLiteI2cAddress); | |
| } | |
| void LIDARLite_changeAddressMultiPwrEn(int numOfSensors, int *pinArray, unsigned char *i2cAddressArray, bool usePartyLine) { | |
| for (int i = 0; i < numOfSensors; i++) { | |
| pinMode(pinArray[i], OUTPUT); // Pin to first LIDAR-Lite Power Enable line | |
| delay(2); | |
| digitalWrite(pinArray[i], HIGH); | |
| delay(20); | |
| LIDARLite_configure(1, addresses_default); | |
| LIDARLite_changeAddress(i2cAddressArray[i], true, addresses_default); // We have to turn off the party line to actually get these to load | |
| } | |
| if (usePartyLine) { | |
| for (int i = 0; i < numOfSensors; i++) { | |
| LIDARLite_write(0x1e, 0x00, i2cAddressArray[i]); | |
| } | |
| } | |
| } | |
| void LIDARLite_configure(int configuration, char LidarLiteI2cAddress) { | |
| switch (configuration) { | |
| case 0: // Default configuration | |
| LIDARLite_write(0x00, 0x00, LidarLiteI2cAddress); | |
| break; | |
| case 1: // Set aquisition count to 1/3 default value, faster reads, slightly | |
| // noisier values | |
| LIDARLite_write(0x04, 0x00, LidarLiteI2cAddress); | |
| break; | |
| case 2: // Low noise, low sensitivity: Pulls decision criteria higher | |
| // above the noise, allows fewer false detections, reduces | |
| // sensitivity | |
| LIDARLite_write(0x1c, 0x20, LidarLiteI2cAddress); | |
| break; | |
| case 3: // High noise, high sensitivity: Pulls decision criteria into the | |
| // noise, allows more false detections, increses sensitivity | |
| LIDARLite_write(0x1c, 0x60, LidarLiteI2cAddress); | |
| break; | |
| } | |
| } | |
| unsigned char LIDARLite_changeAddress(char newI2cAddress, bool disablePrimaryAddress, char currentLidarLiteAddress) { | |
| // Array to save the serial number | |
| unsigned char serialNumber[2]; | |
| unsigned char newI2cAddressArray[1]; | |
| // Read two bytes from 0x96 to get the serial number | |
| Serial.println(" LIDARLite_read(0x96, 2, serialNumber, false, currentLidarLiteAddress)"); | |
| LIDARLite_read(0x96, 2, serialNumber, false, currentLidarLiteAddress); | |
| // Write the low byte of the serial number to 0x18 | |
| LIDARLite_write(0x18, serialNumber[0], currentLidarLiteAddress); | |
| // Write the high byte of the serial number of 0x19 | |
| LIDARLite_write(0x19, serialNumber[1], currentLidarLiteAddress); | |
| // Write the new address to 0x1a | |
| LIDARLite_write(0x1a, newI2cAddress, currentLidarLiteAddress); | |
| Serial.println(" while (newI2cAddress != newI2cAddressArray[0])"); | |
| int cnt =0; | |
| while (newI2cAddress != newI2cAddressArray[0]) { | |
| Serial.println(cnt); | |
| cnt++; | |
| LIDARLite_read(0x1a, 1, newI2cAddressArray, false, currentLidarLiteAddress); | |
| } | |
| Serial.println("WIN!"); | |
| // Choose whether or not to use the default address of 0x62 | |
| if (disablePrimaryAddress) { | |
| LIDARLite_write(0x1e, 0x08, currentLidarLiteAddress); | |
| } else { | |
| LIDARLite_write(0x1e, 0x00, currentLidarLiteAddress); | |
| } | |
| return newI2cAddress; | |
| } | |
  
    
      This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
      Learn more about bidirectional Unicode characters
    
  
  
    
  | int LIDARLite_distance(bool stablizePreampFlag, bool takeReference, char LidarLiteI2cAddress) { | |
| if (stablizePreampFlag) { | |
| // Take acquisition & correlation processing with DC correction | |
| LIDARLite_write(0x00, 0x04, LidarLiteI2cAddress); | |
| } else { | |
| // Take acquisition & correlation processing without DC correction | |
| LIDARLite_write(0x00, 0x03, LidarLiteI2cAddress); | |
| } | |
| // Array to store high and low bytes of distance | |
| byte distanceArray[2]; | |
| // Read two bytes from register 0x8f. (See autoincrement note above) | |
| // Serial.print(" LIDARLite_read(0x8f, 2, distanceArray, true, LidarLiteI2cAddress) "); | |
| Serial.print(" "); | |
| Serial.print(LidarLiteI2cAddress); | |
| Serial.print(" "); | |
| LIDARLite_read(0x8f, 2, distanceArray, true, LidarLiteI2cAddress); | |
| // Shift high byte and add to low byte | |
| int distance = (distanceArray[0] << 8) + distanceArray[1]; | |
| return (distance); | |
| } | |
| void LIDARLite_write(char myAddress, char myValue, char LidarLiteI2cAddress) { | |
| Wire.beginTransmission((int)LidarLiteI2cAddress); | |
| Wire.write((int)myAddress); | |
| Wire.write((int)myValue); | |
| int nackCatcher = Wire.endTransmission(); | |
| if (nackCatcher != 0) { | |
| Serial.println("1 > nack 1"); | |
| } | |
| delay(1); | |
| } | |
| void LIDARLite_read(char myAddress, int numOfBytes, byte arrayToSave[2], bool monitorBusyFlag, char LidarLiteI2cAddress) { | |
| int busyFlag = 0; | |
| if (monitorBusyFlag) { | |
| busyFlag = 1; | |
| } | |
| int busyCounter = 0; | |
| while (busyFlag != 0) { | |
| Wire.beginTransmission((int)LidarLiteI2cAddress); | |
| Wire.write(0x01); | |
| int nackCatcher = Wire.endTransmission(); | |
| if (nackCatcher != 0) { | |
| Serial.println("2> nack 2"); | |
| } | |
| Wire.requestFrom((int)LidarLiteI2cAddress, 1); | |
| busyFlag = bitRead(Wire.read(), 0); | |
| busyCounter++; | |
| if (busyCounter > 9999) { | |
| if (errorReporting) { | |
| int errorExists = 0; | |
| Wire.beginTransmission((int)LidarLiteI2cAddress); | |
| Wire.write(0x01); | |
| int nackCatcher = Wire.endTransmission(); | |
| if (nackCatcher != 0) { | |
| Serial.println("3> nack 3"); | |
| } | |
| Wire.requestFrom((int)LidarLiteI2cAddress, 1); | |
| errorExists = bitRead(Wire.read(), 0); | |
| if (errorExists) { | |
| unsigned char errorCode[] = {0x00}; | |
| Wire.beginTransmission((int)LidarLiteI2cAddress); // Get the slave's attention, tell it we're sending a command byte | |
| Wire.write(0x40); | |
| delay(20); | |
| int nackCatcher = Wire.endTransmission(); // "Hang up the line" so others can use it (can have multiple slaves & masters connected) | |
| if (nackCatcher != 0) { | |
| Serial.println("4> nack 4"); | |
| } | |
| Wire.requestFrom((int)LidarLiteI2cAddress, 1); | |
| errorCode[0] = Wire.read(); | |
| delay(10); | |
| Serial.print("> Error Code from Register 0x40: "); | |
| Serial.println(errorCode[0]); | |
| delay(20); | |
| Wire.beginTransmission((int)LidarLiteI2cAddress); | |
| Wire.write((int)0x00); | |
| Wire.write((int)0x00); | |
| nackCatcher = Wire.endTransmission(); | |
| if (nackCatcher != 0) { | |
| Serial.println("5> nack 5"); | |
| } | |
| } | |
| } | |
| goto bailout; | |
| } | |
| } | |
| if (busyFlag == 0) { | |
| Wire.beginTransmission((int)LidarLiteI2cAddress); | |
| Wire.write((int)myAddress); | |
| int nackCatcher = Wire.endTransmission(); | |
| if (nackCatcher != 0) { | |
| Serial.println("NACK Z"); | |
| } | |
| Wire.requestFrom((int)LidarLiteI2cAddress, numOfBytes); | |
| int i = 0; | |
| if (numOfBytes <= Wire.available()) { | |
| while (i < numOfBytes) { | |
| arrayToSave[i] = Wire.read(); | |
| i++; | |
| } | |
| } | |
| } | |
| if (busyCounter > 9999) { | |
| bailout: | |
| busyCounter = 0; | |
| Serial.println("> Bailout"); | |
| } | |
| } | 
  
    Sign up for free
    to join this conversation on GitHub.
    Already have an account?
    Sign in to comment