Garmin LiDAR-Lite v3HP working…

but at a price.  Here’s the python classes:

v3

####################################################################################################
#
#  Garmin LiDAR-Lite v3 range finder
#
####################################################################################################
class GLLv3:
    i2c = None

    __GLL_ACQ_COMMAND       = 0x00
    __GLL_STATUS            = 0x01
    __GLL_SIG_COUNT_VAL     = 0x02
    __GLL_ACQ_CONFIG_REG    = 0x04
    __GLL_VELOCITY          = 0x09
    __GLL_PEAK_CORR         = 0x0C
    __GLL_NOISE_PEAK        = 0x0D
    __GLL_SIGNAL_STRENGTH   = 0x0E
    __GLL_FULL_DELAY_HIGH   = 0x0F
    __GLL_FULL_DELAY_LOW    = 0x10
    __GLL_OUTER_LOOP_COUNT  = 0x11
    __GLL_REF_COUNT_VAL     = 0x12
    __GLL_LAST_DELAY_HIGH   = 0x14
    __GLL_LAST_DELAY_LOW    = 0x15
    __GLL_UNIT_ID_HIGH      = 0x16
    __GLL_UNIT_ID_LOW       = 0x17
    __GLL_I2C_ID_HIGHT      = 0x18
    __GLL_I2C_ID_LOW        = 0x19
    __GLL_I2C_SEC_ADDR      = 0x1A
    __GLL_THRESHOLD_BYPASS  = 0x1C
    __GLL_I2C_CONFIG        = 0x1E
    __GLL_COMMAND           = 0x40
    __GLL_MEASURE_DELAY     = 0x45
    __GLL_PEAK_BCK          = 0x4C
    __GLL_CORR_DATA         = 0x52
    __GLL_CORR_DATA_SIGN    = 0x53
    __GLL_ACQ_SETTINGS      = 0x5D
    __GLL_POWER_CONTROL     = 0x65

    def __init__(self, address=0x62, rate=10):
        self.i2c = I2C(address)
        self.rate = rate

        #-------------------------------------------------------------------------------------------
        # Set to continuous sampling after initial read.
        #-------------------------------------------------------------------------------------------
        self.i2c.write8(self.__GLL_OUTER_LOOP_COUNT, 0xFF)

        #-------------------------------------------------------------------------------------------
        # Set the sampling frequency as 2000 / Hz:
        # 10Hz = 0xc8
        # 20Hz = 0x64
        # 100Hz = 0x14
        #-------------------------------------------------------------------------------------------
        self.i2c.write8(self.__GLL_MEASURE_DELAY, int(2000 / rate))

        #-------------------------------------------------------------------------------------------
        # Include receiver bias correction 0x04
        #AB! 0x04 | 0x01 should cause (falling edge?) GPIO_GLL_DR_INTERRUPT.  Can GPIO handle this?
        #-------------------------------------------------------------------------------------------
        self.i2c.write8(self.__GLL_ACQ_COMMAND, 0x04 | 0x01)

        #-------------------------------------------------------------------------------------------
        # Acquisition config register:
        # 0x01 Data ready interrupt
        # 0x20 Take sampling rate from MEASURE_DELAY
        #-------------------------------------------------------------------------------------------
        self.i2c.write8(self.__GLL_ACQ_CONFIG_REG, 0x21)


    def read(self):
        #-------------------------------------------------------------------------------------------
        # Distance is in cm hence the 100s to convert to meters.
        # Velocity is in cm between consecutive reads; sampling rate converts these to a velocity.
        # Reading the list from 0x8F seems to get the previous reading, probably cached for the sake
        # of calculating the velocity next time round.
        #-------------------------------------------------------------------------------------------
        dist1 = self.i2c.readU8(self.__GLL_FULL_DELAY_HIGH)
        dist2 = self.i2c.readU8(self.__GLL_FULL_DELAY_LOW)
        distance = (dist1 << 8) + dist2

        if distance == 1:
            raise ValueError("GLL out of range")

        return distance / 100

v3HP

####################################################################################################
#
#  Garmin LiDAR-Lite v3HP range finder
#
####################################################################################################
class GLLv3HP:
    i2c = None

    __GLL_ACQ_COMMAND       = 0x00
    __GLL_STATUS            = 0x01
    __GLL_SIG_COUNT_VAL     = 0x02
    __GLL_ACQ_CONFIG_REG    = 0x04
    __GLL_LEGACY_RESET_EN   = 0x06
    __GLL_SIGNAL_STRENGTH   = 0x0E
    __GLL_FULL_DELAY_HIGH   = 0x0F
    __GLL_FULL_DELAY_LOW    = 0x10
    __GLL_REF_COUNT_VAL     = 0x12
    __GLL_UNIT_ID_HIGH      = 0x16
    __GLL_UNIT_ID_LOW       = 0x17
    __GLL_I2C_ID_HIGHT      = 0x18
    __GLL_I2C_ID_LOW        = 0x19
    __GLL_I2C_SEC_ADDR      = 0x1A
    __GLL_THRESHOLD_BYPASS  = 0x1C
    __GLL_I2C_CONFIG        = 0x1E
    __GLL_PEAK_STACK_HIGH   = 0x26
    __GLL_PEAK_STACK_LOW    = 0x27
    __GLL_COMMAND           = 0x40
    __GLL_HEALTHY_STATUS    = 0x48
    __GLL_CORR_DATA         = 0x52
    __GLL_CORR_DATA_SIGN    = 0x53
    __GLL_POWER_CONTROL     = 0x65

    def __init__(self, address=0x62):
        self.i2c = I2C(address)

        self.i2c.write8(self.__GLL_SIG_COUNT_VAL, 0x80)
        self.i2c.write8(self.__GLL_ACQ_CONFIG_REG, 0x08)
        self.i2c.write8(self.__GLL_REF_COUNT_VAL, 0x05)
        self.i2c.write8(self.__GLL_THRESHOLD_BYPASS, 0x00)

    def read(self):
        acquired = False

        # Trigger acquisition
        self.i2c.write8(self.__GLL_ACQ_COMMAND, 0x01)

        # Poll acquired?
        while not acquired:
            acquired = not (self.i2c.readU8(self.__GLL_STATUS) & 0x01)
        else:    
            dist1 = self.i2c.readU8(self.__GLL_FULL_DELAY_HIGH)
            dist2 = self.i2c.readU8(self.__GLL_FULL_DELAY_LOW)
            distance = (dist1 << 8) + dist2

        return distance / 100

The need for the v3HP is that its I2C conforms to an I2C  deviant added to the Raspberry Pi in March 2017.  It is also smaller and theoretically higher precision.

Trouble is, it comes with several problems:

  • $10 more than the v3
  • radically modified I2C registers missing several beneficial options in the v3 resulting in potentially less efficiency.
  • poor documentation meaning I was pointed at the GitHub sample to work out how to use it.

On the plus side, Penelope has now had a successful first live flight as a result but at a price.  I’m in two minds now whether to get one for Zoe when the only benefit for her is physical size.

3 thoughts on “Garmin LiDAR-Lite v3HP working…

  1. Hi, I try your code with V3, but, i have always the same distance (12.85). Sidewiring, I check many times, the I2C is good, I don’t understand why it is not work.

    • Are you using the v3 or v3HP: the v3 has a socket to attach the rainbow wires; the v3HP has a black cable permanently attach? I never got the interrupt working for the v3 – I always have to call it when I want a value – other than that I had no problem. The v3HP uses a completely different set of I2C registers. It’s interrupt works, but you have to make 3 I2C calls each time you want to read it.

      The main problem with both is the wires they give are too long; only when shorting the wires can I get good reading.

      I’m currently upgrading Zoe with a v3HP and the wires are to long corrupting the I2C for the MPU-9250. I’ve fixed this for both Hermione and Penelope by reducing the wires to about 2/3 maximum.

      Hope that helps?

      Hove

Leave a Reply

Your email address will not be published. Required fields are marked *

This site uses Akismet to reduce spam. Learn how your comment data is processed.