TFmini Lidar functionality

Does anyone here have experience with the TFmini lidar sensor that uses TTL serial to communicate with the arduino?

In what applications have you used it?

With what hardware (mega, uno, due...)?

Did you notice any delays between introducing an object into the laser path and observing a value change on the serial monitor?

How good and reliable is the error handling?

Thanks!

I have used a TFMini with a Mega, Due, and STM32. I am currently using the TFMini with an ESP32. I use the TFMini sitting on a X/Y stabilized platform that sweeps 45 degrees. I find the TFMini to produce a fast response to an object entering its field of view, no noticeable difference. I do not use serial monitor to display the TFMini image that is created.

I'm not sure of your meaning to error handling. I reject all readings over 600cm. On occasion I receive a reading of 65K, which I reject. I found that the serial line, I use hardware serial. I found that the rx/tx wires should be a twisted pair. I use the TFMini in single trigger mode instead of continuous.

thanks,

i have a tfmini and an arduno due. i was playing around with it using the hardware serial1. and i call the get distance function once every 10ms, so 100hz. how do you call it single shot instead of continuous?

i noticed a slight delay between bringing in an object into the path and it appearing on the serial monitor. probably around 0.1-0.2s.

im not running twisted pair, how have they improved your measurements?

my goal is to use the tfmini to measure the height of a drone and use it for altitude hold regulations

I use the following code (MEGA, Due, STM32, and ESP32) for running the TFMini:

TFMini.h

/*
Arduino driver for Benewake TFMini time-of-flight distance sensor. 
by Peter Jansen (December 11/2017)
This code is open source software in the public domain.
THIS SOFTWARE IS PROVIDED ''AS IS'' AND ANY
EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE AUTHOR(S) BE LIABLE FOR ANY
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.  
The names of the contributors may not be used to endorse or promote products
derived from this software without specific prior written permission. 
*/

#if (ARDUINO >= 100)
 #include "Arduino.h"
#else
 #include "WProgram.h"
#endif


// Defines
#define TFMINI_BAUDRATE   115200
#define TFMINI_DEBUGMODE  0

// The frame size is nominally 9 characters, but we don't include the first two 0x59's marking the start of the frame
#define TFMINI_FRAME_SIZE                 7

// Timeouts
#define TFMINI_MAXBYTESBEFOREHEADER       30
#define TFMINI_MAX_MEASUREMENT_ATTEMPTS   10

// States
#define READY                             0
#define ERROR_SERIAL_NOHEADER             1
#define ERROR_SERIAL_BADCHECKSUM          2
#define ERROR_SERIAL_TOOMANYTRIES         3
#define MEASUREMENT_OK                    10


//
// Driver Class Definition
//
class TFMini {
  public: 
    TFMini(void);

    // Configuration
    boolean begin(Stream* _streamPtr);
    void setSingleScanMode();
    
    // Data collection
    uint16_t getDistance();
    uint16_t getRecentSignalStrength();
    void externalTrigger();

  private:
    Stream* streamPtr;
    int state;
    uint16_t distance;
    uint16_t strength;
    
    // Low-level communication
    void setStandardOutputMode();
    void setConfigMode();
    int takeMeasurement();
    
};

TFMini.cpp:

/*
  Arduino driver for Benewake TFMini time-of-flight distance sensor.
  by Peter Jansen (December 11/2017)
  This code is open source software in the public domain.
  THIS SOFTWARE IS PROVIDED ''AS IS'' AND ANY
  EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
  WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
  DISCLAIMED. IN NO EVENT SHALL THE AUTHOR(S) BE LIABLE FOR ANY
  DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
  (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
  ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
  SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
  The names of the contributors may not be used to endorse or promote products
  derived from this software without specific prior written permission.
*/

#include "TFMini.h"

// Constructor
TFMini::TFMini() {
  // Empty constructor
}


boolean TFMini::begin(Stream* _streamPtr) {
  // Store reference to stream/serial object
  streamPtr = _streamPtr;

  // Clear state
  distance = -1;
  strength = -1;
  state = READY;

  // Set standard output mode
  setStandardOutputMode();

  return true;
}


// Public: The main function to measure distance.
uint16_t TFMini::getDistance() {
  int numMeasurementAttempts = 0;
  while (takeMeasurement() != 0) {
    numMeasurementAttempts += 1;
    if (numMeasurementAttempts > TFMINI_MAX_MEASUREMENT_ATTEMPTS) {
      Serial.println ("TF Mini error: too many measurement attempts");
      Serial.println ("Last error:");
      if (state == ERROR_SERIAL_NOHEADER)     Serial.println("ERROR_SERIAL_NOHEADER");
      if (state == ERROR_SERIAL_BADCHECKSUM)  Serial.println("ERROR_SERIAL_BADCHECKSUM");
      if (state == ERROR_SERIAL_TOOMANYTRIES) Serial.println("ERROR_SERIAL_TOOMANYTRIES");
      // Serial.flush();
      state = ERROR_SERIAL_TOOMANYTRIES;
      distance = -1;
      strength = -1;
      return -1;
    }
  }

  if (state == MEASUREMENT_OK) {
    return distance;
  } else {
    return -1;
  }
}

// Public: Return the most recent signal strength measuremenet from the TF Mini
uint16_t TFMini::getRecentSignalStrength() {
  return strength;
}


// Private: Set the TF Mini into the correct measurement mode
void TFMini::setStandardOutputMode() {
  // Set to "standard" output mode (this is found in the debug documents)
  streamPtr->write((uint8_t)0x42);
  streamPtr->write((uint8_t)0x57);
  streamPtr->write((uint8_t)0x02);
  streamPtr->write((uint8_t)0x00);
  streamPtr->write((uint8_t)0x00);
  streamPtr->write((uint8_t)0x00);
  streamPtr->write((uint8_t)0x01);
  streamPtr->write((uint8_t)0x06);
}

// Set configuration mode
void TFMini::setConfigMode() {
  // advanced parameter configuration mode
  streamPtr->write((uint8_t)0x42);
  streamPtr->write((uint8_t)0x57);
  streamPtr->write((uint8_t)0x02);
  streamPtr->write((uint8_t)0x00);
  streamPtr->write((uint8_t)0x00);
  streamPtr->write((uint8_t)0x00);
  streamPtr->write((uint8_t)0x01);
  streamPtr->write((uint8_t)0x02);
}

// Set single scan mode (external trigger)
void TFMini::setSingleScanMode() {
  setConfigMode();
  // setting trigger source to external
  streamPtr->write((uint8_t)0x42);
  streamPtr->write((uint8_t)0x57);
  streamPtr->write((uint8_t)0x02);
  streamPtr->write((uint8_t)0x00);
  streamPtr->write((uint8_t)0x00);
  streamPtr->write((uint8_t)0x00);
  streamPtr->write((uint8_t)0x00);
  streamPtr->write((uint8_t)0x40);
}

// Send external trigger
void TFMini::externalTrigger() {
  setConfigMode();
  // send trigger
  streamPtr->write((uint8_t)0x42);
  streamPtr->write((uint8_t)0x57);
  streamPtr->write((uint8_t)0x02);
  streamPtr->write((uint8_t)0x00);
  streamPtr->write((uint8_t)0x00);
  streamPtr->write((uint8_t)0x00);
  streamPtr->write((uint8_t)0x00);
  streamPtr->write((uint8_t)0x41);
}

// Private: Handles the low-level bits of communicating with the TFMini, and detecting some communication errors.
int TFMini::takeMeasurement() {
  int numCharsRead = 0;
  uint8_t lastChar = 0x00;

  // Step 1: Read the serial stream until we see the beginning of the TF Mini header, or we timeout reading too many characters.
  while (1) {

    if (streamPtr->available()) {
      uint8_t curChar = streamPtr->read();

      if ((lastChar == 0x59) && (curChar == 0x59)) {
        // Break to begin frame
        break;

      } else {
        // We have not seen two 0x59's in a row -- store the current character and continue reading.
        lastChar = curChar;
        numCharsRead += 1;
      }
    }

    // Error detection:  If we read more than X characters without finding a frame header, then it's likely there is an issue with
    // the Serial connection, and we should timeout and throw an error.
    if (numCharsRead > TFMINI_MAXBYTESBEFOREHEADER) {
      state = ERROR_SERIAL_NOHEADER;
      distance = -1;
      strength = -1;
      if (TFMINI_DEBUGMODE == 1) Serial.println("ERROR: no header");
      return -1;
    }

  }

  // Step 2: Read one frame from the TFMini
  uint8_t frame[TFMINI_FRAME_SIZE];

  uint8_t checksum = 0x59 + 0x59;
  for (int i = 0; i < TFMINI_FRAME_SIZE; i++) {
    // Read one character
    while (!streamPtr->available()) {
      // wait for a character to become available
    }
    frame[i] = streamPtr->read();

    // Store running checksum
    if (i < TFMINI_FRAME_SIZE - 2) {
      checksum += frame[i];
    }
  }

  // Step 2A: Compare checksum
  // Last byte in the frame is an 8-bit checksum
  uint8_t checksumByte = frame[TFMINI_FRAME_SIZE - 1];
  if (checksum != checksumByte) {
    state = ERROR_SERIAL_BADCHECKSUM;
    distance = -1;
    strength = -1;
    if (TFMINI_DEBUGMODE == 1) Serial.println("ERROR: bad checksum");
    return -1;
  }


  // Step 3: Interpret frame
  uint16_t dist = (frame[1] << 8) + frame[0];
  uint16_t st = (frame[3] << 8) + frame[2];
  uint8_t reserved = frame[4];
  uint8_t originalSignalQuality = frame[5];


  // Step 4: Store values
  distance = dist;
  strength = st;
  state = MEASUREMENT_OK;

  // Return success
  return 0;
}

Add "

#include "TFMini.h"
TFMini tfmini;

" to your declare section.

setup()

  // Initialize the TFMini LIDAR
  tfmini.begin(&SerialTFMini);
  vTaskDelay( pdMS_TO_TICKS( 3 ) );
  // Initialize single measurement mode with external trigger
  tfmini.setSingleScanMode();

My task code that runs the TFMini

void fDoLIDAR( void * pvParameters )
{
  int iLIDAR_Distance = 0;
  //  int iLIDAR_Strength = 0;
  while (1)
  {
    xEventGroupWaitBits (eg, evtDoLIDAR, pdTRUE, pdTRUE, portMAX_DELAY) ;
    tfmini.externalTrigger();
    iLIDAR_Distance = tfmini.getDistance();
    if ( iLIDAR_Distance > LIDAR_Max_Distance )
    {
      Serial.print ( " TFMini distance issue " );
      Serial.println (  iLIDAR_Distance );
    }
    xSemaphoreTake( sema_LIDAR_INFO, xSemaphoreTicksToWait );
    x_LIDAR_INFO.Range[x_LIDAR_INFO.CurrentCell] = iLIDAR_Distance;
    xSemaphoreGive( sema_LIDAR_INFO );
    xEventGroupSetBits( eg, evtLIDAR_ServoAspectChange );
  }
  vTaskDelete( NULL );
}

You can see that the code, posted, has a single trigger mode.

When I ran the TFMini on the DUE, I ran uMT and ran the TFMini round robin fashion instead of on a timer. If I ran the DUE now, I'd use the freeRTOS library that is available for the Arduino product line.

By round robin, on the ESP32, I have the task to take a TFMini measurement is triggered by the completion of the servo adjust task, the servo adjust task triggers the TFMini task. Each task runs on a different core, quite fast.

Twisted pair, greatly reduced the number of 65K+ distance readings., as does having the TFMini wires to a soldered connection instead of a breadboarded connection. Take a wire for rx and a wire for tx and twist them together.

whoa! that helps a bunch, the library i had did not have the singlescan mode in it, so i corrected the library.

all is working, except occasionally upon start-up the sensor will deliver values of 65k continously. until i replug the sensor, then it provides correct values.

what could be causing this?

I have the same 65K problem.

Timmy_the_dear:
I have the same 65K problem.

I, also, used to have the 65K issue, until I put the TFMini onto a prototype board, made cable runs and soldered in connector plugs. I had found that the 65K issue stemmed, mainly, from poor physical connections. I had, also, built a watch dog to handle the 65K issue. When 300 65K's were received in a row the uController reset its self.