SEN0648 TOF laser ranging sensor-50m

TOF laser ranging sensor-50m

Introduction

The TOF laser ranging sensor is a new generation of laser ranging sensor based on dTOF (direct Time of Flight) technology. It has undergone a comprehensive upgrade in hardware design and algorithm level, with a ranging blind area of less than 5cm, a maximum range of up to 50m (depending on the reflectivity of the environment), and a ranging accuracy within ±3cm (typical value). It performs stably in dynamic environments, with a high resistance to environmental light interference of up to 100K LUX, making it suitable for both indoor and outdoor strong light environments. It supports multiple communication interfaces such as UART, I2C, I/O, meeting the needs of different development architectures.

The TOF laser ranging sensor-50 meters is highlighted by its small size (weighing only 7.5g) and high cost performance, designed specifically for scenarios that need to integrate laser ranging functions on a large scale, such as consumer electronics, robots and drones, etc. Its compact design allows it to be easily embedded in space-constrained devices while maintaining high-performance ranging capabilities.

Application Scenarios

  1. Robot Obstacle Avoidance and Navigation

    By covering the robot's detection area with multiple sensors and combining high frame rate (up to 100Hz) data output, dynamic obstacle avoidance and path planning can be achieved.

  2. Drone Altitude Hold and Terrain Following

    Installed at the bottom of the drone, it measures the distance from the ground in real time, assisting in precise altitude hold and landing, especially in uneven ground scenarios.

  3. Industrial Inspection and Automation

    Used for material level detection (such as warehouse material bin height monitoring), hydraulic stacking shape analysis, or object counting and positioning on the production line.

  4. Smart Traffic and Traffic Flow Monitoring

    Deployed on road gantries or parking lots, it can count traffic flow, vehicle speed and parking space status, supporting the construction of intelligent traffic systems.

  5. Consumer Electronics and Smart Home

    Integrated into smart locks, fitness equipment or automatic doors, it can achieve gesture recognition, motion monitoring and other interactive functions.

Product Parameters

Size Parameters

Tutorial

Preparation

Serial Output

UART mode has two output methods: Active Output and Query Output, which can be switched by modifying the data output method on the host computer software. Connect the TOFSense-F/F2 series products to the host computer software through the USB to TTL module (refer to the data manual for the line sequence and power supply voltage). After successful recognition, click to enter the settings page, configure the parameters and click the write parameters button to save the parameters. After successful parameter writing, you can read the parameters once to confirm whether the parameters are successfully written.

Active Output

UART active output mode can only be used in single module.

The interface type is set to UART, the data output method is set to ACTIVE, and the UART active output mode is configured as shown in the figure. In this mode, the module defaults to output measurement information actively at a frequency of 50Hz, and the output format follows the NLink_TOFSense_Frame0 protocol.

Wiring Diagram

Sample Code

HardwareSerial mySerial(1);

typedef struct {
  unsigned char id;               //ID of the TOF module
  unsigned long system_time;      //Time elapsed since the TOF module is powered on, unit: ms
  float dis;                      //Distance output by the TOF module, unit: m
  unsigned char dis_status;       //Distance status indication output by the TOF module
  unsigned int signal_strength;   //Signal strength output by the TOF module
  unsigned char range_precision;  //Reference value of repeatability ranging accuracy output by the TOF module, valid for TOFSense-F series, unit: cm
} tof_parameter;                  //Structure of the decoded TOF data

/**
  @brief  Read data from the serial port
  @param  buf Buffer to store the read data
  @param  len Number of bytes to read
  @return  The return value is the actual number of bytes read
*/
size_t readN(uint8_t *buf, size_t len);

/**
  @brief  Read a complete data packet
  @param  buf Buffer to store the read data
  @return  True means success, false means failure
*/
bool recdData(tof_parameter *buf);

void setup() {
  Serial.begin(115200);
  mySerial.begin(921600, SERIAL_8N1, 4, 5);  //RX,TX
}

void loop() {
  tof_parameter tof0;  //Define a structure to store the decoded data
  recdData(&tof0);
  // Print data through the serial port
  Serial.print("id:");
  Serial.println(tof0.id);
  Serial.print("system_time:");
  Serial.println(tof0.system_time);
  Serial.print("dis:");
  Serial.println(tof0.dis);
  Serial.print("dis_status:");
  Serial.println(tof0.dis_status);
  Serial.print("signal_strength:");
  Serial.println(tof0.signal_strength);
  Serial.print("range_precision:");
  Serial.println(tof0.range_precision);
  Serial.println("");

  delay(1000);
}

size_t readN(uint8_t *buf, size_t len) {
  size_t offset = 0, left = len;
  int16_t Tineout = 1500;
  uint8_t *buffer = buf;
  long curr = millis();
  while (left) {
    if (mySerial.available()) {
      buffer[offset] = mySerial.read();
      offset++;
      left--;
    }
    if (millis() - curr > Tineout) {
      break;
    }
  }
  return offset;
}

bool recdData(tof_parameter *buf) {
  uint8_t rx_buf[16];  //Serial receive array
  int16_t Tineout = 5000;
  uint8_t ch;
  bool ret = false;
  uint8_t Sum;
  while (mySerial.available() > 0) {
    mySerial.read();
  }
  long timeStart = millis();

  while (!ret) {
    if (millis() - timeStart > Tineout) {
      break;
    }
    if (readN(&ch, 1) == 1) {
      if (ch == 0x57) {
        rx_buf[0] = ch;
        if (readN(&ch, 1) == 1) {
          if (ch == 0x00) {
            rx_buf[1] = ch;
            if (readN(&rx_buf[2], 14) == 14) {
              Sum = 0;
              for (int i = 0; i < 15; i++)
                Sum += rx_buf[i];
              if (Sum == rx_buf[15]) {
                buf->id = rx_buf[3];                                                                                                                                                   //Get the id of the TOF module
                buf->system_time = (unsigned long)(((unsigned long)rx_buf[7]) << 24 | ((unsigned long)rx_buf[6]) << 16 | ((unsigned long)rx_buf[5]) << 8 | (unsigned long)rx_buf[4]);  //Get the time elapsed since the TOF module is powered on
                buf->dis = ((float)(((long)(((unsigned long)rx_buf[10] << 24) | ((unsigned long)rx_buf[9] << 16) | ((unsigned long)rx_buf[8] << 8))) / 256)) / 1000.0;                 //Get the distance output by the TOF module
                buf->dis_status = rx_buf[11];                                                                                                                                          //Get the distance status indication output by the TOF module
                buf->signal_strength = (unsigned int)(((unsigned int)rx_buf[13] << 8) | (unsigned int)rx_buf[12]);                                                                     //Get the signal strength output by the TOF module
                buf->range_precision = rx_buf[14];                                                                                                                                     //Get the reference value of repeatability ranging accuracy output by the TOF module
                ret = true;
              }
            }
          }
        }
      }
    }
  }
  return ret;
}

Output Results

Query Output

UART query output mode can be used in single module.

The interface type is set to UART, the data output method is set to INQUIRE, and the UART query output mode is configured as shown in the figure. After writing the parameters, the data will no longer be actively reported. In this mode, the controller needs to send a query command containing the module ID to the expected query module, and the module can output a frame of measurement information. The query frame format follows the NLink_TOFSense_Read_Frame0 protocol, and the output frame format follows the NLink_TOFSense_Frame0 protocol.

Wiring Diagram

Sample Code

HardwareSerial mySerial(1);

typedef struct {
  unsigned char id;               //ID of the TOF module
  unsigned long system_time;      //Time elapsed since the TOF module is powered on, unit: ms
  float dis;                      //Distance output by the TOF module, unit: m
  unsigned char dis_status;       //Distance status indication output by the TOF module
  unsigned int signal_strength;   //Signal strength output by the TOF module
  unsigned char range_precision;  //Reference value of repeatability ranging accuracy output by the TOF module, valid for TOFSense-F series, unit: cm
} tof_parameter;                  //Structure of the decoded TOF data

/**
  @brief  Read data from the serial port
  @param  buf Buffer to store the read data
  @param  len Number of bytes to read
  @return  The return value is the actual number of bytes read
*/
size_t readN(uint8_t *buf, size_t len);

/**
  @brief  Read a complete data packet
  @param  buf Buffer to store the read data
  @param  id Module ID
  @return  True means success, false means failure
*/
bool recdData(tof_parameter *buf, uint8_t id = 0);

void setup() {
  Serial.begin(115200);
  mySerial.begin(921600, SERIAL_8N1, 4, 5);  //RX,TX
}

void loop() {
  tof_parameter tof0;  //Define a structure to store the decoded data
  recdData(&tof0, 0);
  // Print data through the serial port
  Serial.print("id:");
  Serial.println(tof0.id);
  Serial.print("system_time:");
  Serial.println(tof0.system_time);
  Serial.print("dis:");
  Serial.println(tof0.dis);
  Serial.print("dis_status:");
  Serial.println(tof0.dis_status);
  Serial.print("signal_strength:");
  Serial.println(tof0.signal_strength);
  Serial.print("range_precision:");
  Serial.println(tof0.range_precision);
  Serial.println("");

  delay(1000);
}

size_t readN(uint8_t *buf, size_t len) {
  size_t offset = 0, left = len;
  int16_t Tineout = 1500;
  uint8_t *buffer = buf;
  long curr = millis();
  while (left) {
    if (mySerial.available()) {
      buffer[offset] = mySerial.read();
      offset++;
      left--;
    }
    if (millis() - curr > Tineout) {
      break;
    }
  }
  return offset;
}

bool recdData(tof_parameter *buf, uint8_t id) {
  uint8_t rx_buf[16];  //Serial receive array
  int16_t Tineout = 5000;
  uint8_t ch;
  bool ret = false;
  uint8_t Sum;
  uint8_t cmdBuf[8] = { 0x57, 0x10, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0x00 };
  cmdBuf[4] = id;
  cmdBuf[7] = 0;
  for (int i = 0; i < 7; i++)
    cmdBuf[7] += cmdBuf[i];
  long timeStart = millis();
  long timeStart1 = 0;

  while (!ret) {
    if (millis() - timeStart > Tineout) {
      break;
    }

    if ((millis() - timeStart1) > 1000) {
      while (mySerial.available() > 0) {
        mySerial.read();
      }
      mySerial.write(cmdBuf, 8);
      timeStart1 = millis();
    }

    if (readN(&ch, 1) == 1) {
      if (ch == 0x57) {
        rx_buf[0] = ch;
        if (readN(&ch, 1) == 1) {
          if (ch == 0x00) {
            rx_buf[1] = ch;
            if (readN(&rx_buf[2], 14) == 14) {
              Sum = 0;
              for (int i = 0; i < 15; i++)
                Sum += rx_buf[i];
              if (Sum == rx_buf[15]) {
                buf->id = rx_buf[3];                                                                                                                                                   //Get the id of the TOF module
                buf->system_time = (unsigned long)(((unsigned long)rx_buf[7]) << 24 | ((unsigned long)rx_buf[6]) << 16 | ((unsigned long)rx_buf[5]) << 8 | (unsigned long)rx_buf[4]);  //Get the time elapsed since the TOF module is powered on
                buf->dis = ((float)(((long)(((unsigned long)rx_buf[10] << 24) | ((unsigned long)rx_buf[9] << 16) | ((unsigned long)rx_buf[8] << 8))) / 256)) / 1000.0;                 //Get the distance output by the TOF module
                buf->dis_status = rx_buf[11];                                                                                                                                          //Get the distance status indication output by the TOF module
                buf->signal_strength = (unsigned int)(((unsigned int)rx_buf[13] << 8) | (unsigned int)rx_buf[12]);                                                                     //Get the signal strength output by the TOF module
                buf->range_precision = rx_buf[14];                                                                                                                                     //Get the reference value of repeatability ranging accuracy output by the TOF module
                ret = true;
              }
            }
          }
        }
      }
    }
  }
  return ret;
}

Output Results

IIC Output

IIC mode can be used in both single module and cascade. In IIC communication mode, the controller sends a read frame to the expected query module with a specified slave address according to the IIC communication timing, and can obtain the distance and other related information of the module. In addition, parameters such as the module's output mode can also be changed through IIC communication. The format of the read frame and write frame follows the NLink_TOFSense_IIC_Frame0 protocol.

When the module is in UART mode (note that the host computer software cannot recognize the module in IIC mode), connect the TOFSense series products to the host computer software through the USB to TTL module (refer to the data manual for the line sequence and power supply voltage). After successful recognition, click to enter the settings page, configure the parameters and click the write parameters button to save the parameters. Note: After switching to IIC mode, you can refer to the method in the FAQ section to change back to UART mode.

[!WARNING]

Please remember your baud rate (Baudeate) before modifying the configuration, so as to switch back to UART mode later.

Wiring Diagram

Arduino Sample Code

#include <Wire.h>  //I2C library

#define deviceaddress 0x08

typedef struct {
  uint8_t id;                //ID
  uint8_t interface_mode;    //Communication interface mode, 0-UART, 1-CAN, 2-I/O, 3-IIC
  uint32_t uart_baudrate;    //UART baud rate
  uint32_t system_time;      //System time
  float dis;                 //Distance
  uint16_t dis_status;       //Distance status indication
  uint16_t signal_strength;  //Signal strength
  uint8_t range_precision;   //Ranging accuracy
} tof_parameter;             //Parameters output by TOFSense-F

tof_parameter tof0;  //Define a structure to store the decoded data

uint8_t DATA[4] = { 0 };

uint8_t bbt[4] = { 0x00, 0xc2, 0x01, 0x00 };

void i2c_writeN(uint8_t registerAddress, uint8_t *buf, size_t len) {

  Wire.beginTransmission(deviceaddress);
  Wire.write(registerAddress);  // MSB
  Wire.write(buf, len);
  Wire.endTransmission();
  // delay(4);
}

int16_t i2c_readN(uint8_t registerAddress, uint8_t *buf, size_t len) {
  uint8_t i = 0;
  Wire.beginTransmission(deviceaddress);
  Wire.write(registerAddress);
  if (Wire.endTransmission(false) != 0) {
    return -1;
  }

  Wire.requestFrom(deviceaddress, len);
  delay(100);
  while (Wire.available()) {
    buf[i++] = Wire.read();
  }
  return i;
}

bool recdData() {
  uint8_t pdata[48];  //Read cache array
  // Serial.println(i2c_readN(0x00, iic_read_buff, 48));
  if (i2c_readN(0x00, pdata, 32) == 32) {
    if (i2c_readN(0x20, &pdata[32], 16) == 16) {
      tof0.interface_mode = pdata[0x0c] & 0x07;
      tof0.id = pdata[0x0d];
      tof0.uart_baudrate = (uint32_t)(((uint32_t)pdata[0x10]) | ((uint32_t)pdata[0x11] << 8) | ((uint32_t)pdata[0x12] << 16) | ((uint32_t)pdata[0x13] << 24));
      tof0.system_time = (uint32_t)(((uint32_t)pdata[0x20]) | ((uint32_t)pdata[0x21] << 8) | ((uint32_t)pdata[0x22] << 16) | ((uint32_t)pdata[0x23] << 24));
      tof0.dis = (float)(((uint32_t)pdata[0x24]) | ((uint32_t)pdata[0x25] << 8) | ((uint32_t)pdata[0x26] << 16) | ((uint32_t)pdata[0x27] << 24)) / 1000;
      tof0.dis_status = (uint16_t)(((uint16_t)pdata[0x28]) | ((uint16_t)pdata[0x29] << 8));
      tof0.signal_strength = (uint16_t)(((uint16_t)pdata[0x2a]) | ((uint16_t)pdata[0x2ab] << 8));
      tof0.range_precision = pdata[0x2c];
    } else
      return false;
  } else
    return false;
  return true;
}

void setup() {
  Wire.begin(5, 4);  // initialise the connection
  Serial.begin(115200);
  // i2c_writeN(0x10, bbt, 4);
}

void loop() {
  recdData();

  //Print data through the serial port
  Serial.print("id:");
  Serial.println(tof0.id);
  Serial.print("interface_mode:");
  Serial.println(tof0.interface_mode);
  Serial.print("uart_baudrate:");
  Serial.println(tof0.uart_baudrate);
  Serial.print("system_time:");
  Serial.println(tof0.system_time);
  Serial.print("dis:");
  Serial.println(tof0.dis);
  Serial.print("dis_status:");
  Serial.println(tof0.dis_status);
  Serial.print("signal_strength:");
  Serial.println(tof0.signal_strength);
  Serial.print("range_precision:");
  Serial.println(tof0.range_precision);
  Serial.println("");

  delay(1000);  //Query every 1000ms
}

Output Results

I/O Output

In I/O output mode, it can only be used in single module. The module cannot output ranging value. TX/CAN_L and RX/CAN_H output complementary levels. The levels of the two signal lines are opposite. The high level is 3.3V and the low level is 0V. In addition, it should be noted that the output current is small, and it should be noted whether it can drive other devices when driving other devices. If it cannot be driven directly, it can be driven through relays and other methods.

When the module is in UART mode (note that the host computer software cannot recognize the module in I/O mode), connect the TOFSense series products to the host computer software through the USB to TTL module (refer to the data manual for the line sequence and power supply voltage). After successful recognition, click to enter the settings page, configure the parameters and click the write parameters button to save the parameters. Note: After switching to I/O mode, if you need to change Band_Start, Bandwidth and other parameters, you can refer to the method in the FAQ section to switch back to UART mode for configuration.

[!WARNING]

Please remember your baud rate (Baudeate) before modifying the configuration, so as to switch back to UART mode later.

Single Threshold

The interface type is set to IO, Band Start is set to 1000, Band Width is set to 0, IO single threshold configuration is as shown in the figure, after writing the parameter, the module restarts and no longer outputs ranging value but outputs high and low level.

According to the above settings, the threshold value=Band Start=1000(mm), in this mode, when the ranging value<1m, RX is high level, TX is low level, when the ranging value>1m, RX is low level, TX is high level.

Example: When the ranging value is 0.3 meters, RX is high level, TX is low level, when the ranging value increases to 1.2 meters, RX is high level, TX is low level.

Double Threshold

The interface type is set to IO, the hysteresis start point Band Start is set to 1000, the hysteresis width Band Width is set to 500, and the IO double threshold configuration is as shown in the figure. After writing the parameters, the module restarts and no longer outputs ranging values but outputs high and low levels.

According to the above settings, the distance value is converted into high and low level output through hysteresis comparison. When the distance changes from small to large and exceeds the high threshold, or from large to small and is lower than the low threshold, the I/O port level is reversed.

For example, based on the above settings, the low threshold is 1 meter, and the high threshold is 1.5 meters. (Low threshold=Hysteresis start point Band Start, High threshold=Hysteresis start point Band Start + Hysteresis width Band Width)

When the ranging value is 0.3 meters, RX is high level, TX is low level,

When the ranging value increases to 1.2 meters, RX is high level, TX is low level,

When the ranging value continues to increase beyond 1.5 meters, the level is reversed, RX is low level, TX is high level.

When the ranging value drops from more than 1.5 meters to 1.2 meters, RX is low level, TX is high level,

When the ranging value continues to drop below 1 meter, the level is reversed, RX is high level, TX is low level.

Hysteresis comparison schematic diagram is as shown in the figure

Frequently Asked Questions

Why can't the host computer software recognize the module after switching to IIC or I/O mode? How to switch between different communication modes?

Currently, the host computer software only supports the recognition of modules in UART mode. In UART mode, you can configure the module to IIC or I/O communication mode by entering the settings page after the host computer successfully recognizes it; In IIC communication mode, you can switch back to UART or I/O mode by sending instructions to the module through IIC communication according to the IIC communication protocol; In addition, without IIC test environment or after switching to I/O mode, you can switch back to UART mode in the following ways:

  1. Users need to prepare a USB to TTL module that supports 921600 baud rate (CP2102 is recommended) and install the corresponding driver program. Connect the TX, RX, and 5V of the USB to TTL module to the corresponding pins of the TOF module, and do not connect the GND pin for the time being, then plug the USB to TTL module into the computer.

  2. Open the host computer software, click to enter the serial port debugging assistant, change the baud rate to the baud rate you set before (if the baud rate has not been modified, it is 921600), select the COM port corresponding to the USB to TTL module and then click to connect to the COM port (in most cases, it will connect automatically). In the single send text box, enter 54 20 00 ff 00 ff ff ff ff 00 ff ff 00 10 0e ff ff ff ff ff ff ff ff ff ff ff 00 ff ff ff ff 7c, in the timed send bar at the bottom right, change the send interval to 20ms, and then check timed send.

  3. At this time, connect the GND of the USB to TTL module to the GND pin of the TOF module, the module will switch to UART mode and start outputting data, at this time uncheck the timed send button, then unplug the USB to TTL module and re-power the module, then click the recognition button on the main page to recognize the module.

  4. If the switch fails, unplug the USB to TTL module and repeat the whole process. Do not plug and unplug the GND pin multiple times when sending commands. If the module can be recognized normally but the serial port output data is abnormal, you can manually switch to UART mode in the settings page.

    DFshopping_car1.png DFRobot Store Purchase Link