Sanderi44 / Lidar-Lite

C++ and python libraries for getting data from the Lidar-Lite sensor
40 stars 24 forks source link

faster getDistance #7

Closed nicewook closed 6 years ago

nicewook commented 6 years ago

first of all, I get helped your code a lot. thanks. :-) I found better way to speed up measure rate

Now

  def getDistance(self):
    self.writeAndWait(self.distWriteReg, self.distWriteVal)
    dist1 = self.readAndWait(self.distReadReg1)
    dist2 = self.readAndWait(self.distReadReg2)
    return (dist1 << 8) + dist2

Better Way

  def readDistAndWait(self, register, address=None):
    if address == None:
      address = self.address

    res = self.bus.read_i2c_block_data(address, register, 2)
    time.sleep(0.02)
    return (res[0] << 8 | res[1])

  def getDistance(self, address=None):
    if address == None:
      address = self.address
    self.writeAndWait(self.distWriteReg, self.distWritePlusVal, address)
    dist = self.readDistAndWait(self.distReadReg1, address)
    return dist
Sanderi44 commented 6 years ago

This looks good to me. Please make a pull request and I will merge