fab-lab.eu
Published

Complete Orientation in 3D space - LIDAR + 9DOF = 10DOF

Always wanted to know the orientation of my laser distance measurement in 3D space: heading, roll, pitch and distance ready for new projects

IntermediateFull instructions provided6,367
Complete Orientation in 3D space - LIDAR + 9DOF = 10DOF

Things used in this project

Hardware components

LIDAR-lite
the one you need ;-) if you want a higher sampling rate go with the V2 ... use I2C
×1
pico-Platinchen
could be an Arduino Mini Pro with 3.3V too + an BNO055 (Bosch Sensortec)
×1
5V to 3.3V regulator
any convertor you like
×1
Timing Pulley 18T (Pair) Silver
×1
Timing Pulley 90T-Blue
Timing Pulley 90T-Blue ADD a SLICE to it (!)
×1
Timing Belt 123T (Pair)
×1
25mm DC Motor Pack-Blue
any DC motor with 4mm and > 130 rpm
×1
Slip Ring with Flange - 22mm diameter, 6 wires, max 240V @ 2A
that will make the trick, so you can spin the LiDAR for ever - decoupling the cables
×1

Story

Read more

Custom parts and enclosures

LIDAR - mounting base

LIDAR - slip-ring adapter to gear

LIDAR - top mount 1/2

LIDAR - top mount 2/2

Code

Arduino (TM) sketch with 9DOF and distance

C/C++
/* 

http://pulsedlight3d.com

This sketch demonstrates getting distance with the LIDAR-Lite Sensor

It utilizes the 'Arduino I2C Master Library' from DSS Circuits:
http://www.dsscircuits.com/index.php/articles/66-arduino-i2c-master-library 

You can find more information about installing libraries here:
http://arduino.cc/en/Guide/Libraries

Fab-lab.eu added BNO055 support into this project

*/

#include <I2C.h>
#define    LIDARLite_ADDRESS   0x62          // Default I2C Address of LIDAR-Lite.
#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.

#include "NAxisMotion.h"        //Contains the bridge code between the API and the Arduino Environment
#include <Wire.h>
NAxisMotion mySensor;         //Object that for the sensor 


void setup(){
  Serial.begin(9600); //Opens serial connection at 9600bps.     
  I2c.begin(); // Opens & joins the irc bus as master
  delay(100); // Waits to make sure everything is powered up before sending or receiving data  
  I2c.timeOut(50); // Sets a timeout to ensure no locking up of sketch if I2C communication fails

// scan for i2c devices
  byte error, address;
  int nDevices;
  Serial.println("Scanning...");
  nDevices = 0;
  for(address = 1; address < 127; address++ ) 
  {
    Wire.beginTransmission(address);
    error = Wire.endTransmission();
    if (error == 0)
    {
      Serial.print("I2C device found at address 0x");
      if (address<16) 
        Serial.print("0");
      Serial.print(address,HEX);
      Serial.println("  !");
      nDevices++;
    }
    else if (error==4) 
    {
      Serial.print("Error at address 0x");
      if (address<16) 
        Serial.print("0");
      Serial.println(address,HEX);
    }    
  }
  if (nDevices == 0)
    Serial.println("No I2C devices found\n");
  else
    Serial.println("done\n");

  mySensor.initSensor();          //The I2C Address can be changed here inside this function in the library
  mySensor.setOperationMode(OPERATION_MODE_NDOF);   //Can be configured to other operation modes as desired
  mySensor.setUpdateMode(MANUAL);	//The default is AUTO. Changing to MANUAL requires calling the relevant update functions prior to calling the read functions

}

void loop(){
  // Write 0x04 to register 0x00
  uint8_t nackack = 100; // Setup variable to hold ACK/NACK resopnses     
  while (nackack != 0){ // While NACK keep going (i.e. continue polling until sucess message (ACK) is received )
    nackack = I2c.write(LIDARLite_ADDRESS,RegisterMeasure, MeasureValue); // Write 0x04 to 0x00
    delay(1); // Wait 1 ms to prevent overpolling
  }

  byte distanceArray[2]; // array to store distance bytes from read function
  
  // Read 2byte distance from register 0x8f
  nackack = 100; // Setup variable to hold ACK/NACK resopnses     
  while (nackack != 0){ // While NACK keep going (i.e. continue polling until sucess message (ACK) is received )
    nackack = I2c.read(LIDARLite_ADDRESS,RegisterHighLowB, 2, distanceArray); // Read 2 Bytes from LIDAR-Lite Address and store in array
    delay(1); // Wait 1 ms to prevent overpolling
  }
  int distance = (distanceArray[0] << 8) + distanceArray[1];  // Shift high byte [0] 8 to the left and add low byte [1] to create 16-bit int
  
  // Print Distance
  Serial.print(" D: ");

  Serial.print(distance);
  Serial.print("cm ");
  
  mySensor.updateEuler();        //Update the Euler data into the structure of the object
  mySensor.updateCalibStatus();  //Update the Calibration Status

   Serial.print(" H: ");
    Serial.print(mySensor.readEulerHeading()); //Heading data
    Serial.print("deg ");

    Serial.print(" R: ");
    Serial.print(mySensor.readEulerRoll()); //Roll data
    Serial.print("deg");

    Serial.print(" P: ");
    Serial.print(mySensor.readEulerPitch()); //Pitch data
    Serial.print("deg ");
    
    Serial.print(" A: ");
    Serial.print(mySensor.readAccelCalibStatus());  //Accelerometer Calibration Status (0 - 3)
	
    Serial.print(" M: ");
    Serial.print(mySensor.readMagCalibStatus());    //Magnetometer Calibration Status (0 - 3)
	
    Serial.print(" G: ");
    Serial.print(mySensor.readGyroCalibStatus());   //Gyroscope Calibration Status (0 - 3)
	
    Serial.print(" S: ");
    Serial.print(mySensor.readSystemCalibStatus());   //System Calibration Status (0 - 3)

    Serial.println();
   
}

Ardunio I2C sample code for LIDAR-lite giving distance

BNO055 (9DOF) library

Credits

fab-lab.eu

fab-lab.eu

22 projects • 275 followers
Maker!

Comments