Introduction
TOF Laser Ranging Sensor is a new generation of laser ranging sensor based on dTOF (Direct Time of Flight) technology. It has been fully upgraded in hardware design and algorithm level, with a ranging blind zone of less than 5cm and a maximum range of up to 25m (specifically depending on the environmental reflection rate), ranging accuracy within ±3cm (typical value), especially stable performance in dynamic environments, resistance to environmental light interference up to 100K LUX, suitable for indoor and outdoor strong light environments. It supports multiple communication interfaces such as UART, I2C, I/O, etc., to meet different development architecture needs.
The TOF Laser Ranging Sensor-25m is a highlight for its small size (weighing only 7.5g) and high cost performance, designed for scenarios that require large-scale integration of laser ranging functions, 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
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.
Drone Altitude Hold and Terrain Following
Installed at the bottom of the drone, it measures the distance to the ground in real time, assisting in precise altitude hold and landing, especially in uneven terrain scenarios.
Industrial Inspection and Automation
Used for material level detection (such as warehouse material bin height monitoring), hydraulic pile shape analysis, or object counting and positioning on production lines.
Smart Traffic and Traffic Flow Monitoring
Deployed on road gantries or parking lots, it counts traffic flow, vehicle speed and parking space status, supporting the construction of intelligent traffic systems.
Consumer Electronics and Smart Home
Integrated into smart locks, fitness equipment or automatic doors, it realizes gesture recognition, motion monitoring and other interactive functions.
Product Parameters
- Refresh rate: 100Hz
- Classic ranging range: 0.05~25m
- Classic ranging accuracy: ±3cm
- Wavelength: 905nm
- Resistance to ambient light: 100K LUX illuminance
- Field of view (FOV): 1~2°
- Power supply voltage: 4.3V~5.2V
- Power consumption: 250mW
- Communication interface: UART/IIC/IO
- IIC default slave address: 0x80
- Working temperature: -10℃~60℃
- Size: 22.7 mm *28.0 mm *13.6mm
- Product weight: 7.5g
Dimension Parameters

User Guide
Preparation
- Hardware
- TOF Laser Ranging Sensor-25m
- ESP32 series development board
- Software
- Sensor host computer, click to download the host computer
- Arduino IDE, click to download Arduino IDE
Serial Output
UART mode has two output modes: Active Output and Query Output. The two output modes can be switched by modifying the data output mode 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 wire sequence and power supply voltage), after successful recognition, click to enter the settings page, configure the parameters and then click the write parameters button to save the parameters, after successfully writing the parameters, you can read the parameters once to confirm whether the parameters are written successfully.
Active Output
UART active output mode can only be used in single module mode.
The interface type is set to UART, the data output mode 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 complies with 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 was powered on, in ms
float dis; //Distance output by the TOF module, in meters
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 repeat ranging accuracy output by the TOF module, valid for TOFSense-F series, in cm
} tof_parameter; //Decoded TOF data structure
/**
@brief Read data in the serial port
@param buf Storage for the read data
@param len Number of bytes to read
@return The return value is the number of bytes actually read
*/
size_t readN(uint8_t *buf, size_t len);
/**
@brief Read a complete data packet
@param buf Storage for 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]; //Take 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]); //Take the time elapsed since the TOF module was 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; //Take the distance output by the TOF module
buf->dis_status = rx_buf[11]; //Take 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]); //Take the signal strength output by the TOF module
buf->range_precision = rx_buf[14]; //Take the reference value of repeat ranging accuracy output by the TOF module
ret = true;
}
}
}
}
}
}
}
return ret;
}
Output Result

Query Output
UART query output mode can be used in single module mode.
The interface type is set to UART, the data output mode is set to INQUIRE, and the UART query output mode is configured as shown in the figure. After writing the parameters, it will no longer actively report data. 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 was powered on, in ms
float dis; //Distance output by the TOF module, in meters
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 repeat ranging accuracy output by the TOF module, valid for TOFSense-F series, in cm
} tof_parameter; //Decoded TOF data structure
/**
@brief Read data in the serial port
@param buf Storage for the read data
@param len Number of bytes to read
@return The return value is the number of bytes actually read
*/
size_t readN(uint8_t *buf, size_t len);
/**
@brief Read a complete data packet
@param buf Storage for 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]; //Take 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]); //Take the time elapsed since the TOF module was 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; //Take the distance output by the TOF module
buf->dis_status = rx_buf[11]; //Take 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]); //Take the signal strength output by the TOF module
buf->range_precision = rx_buf[14]; //Take the reference value of repeat ranging accuracy output by the TOF module
ret = true;
}
}
}
}
}
}
}
return ret;
}
Output Result

IIC Output
IIC mode can be used in single module and cascade mode. In IIC communication mode, the controller sends a read frame to the expected query module with the specified slave address according to the IIC communication timing, and can obtain the distance and other related information of the module. In addition, you can also change the output mode and other parameters of the module through IIC communication. The read frame and write frame format follow the NLink_TOFSense_IIC_Frame0 protocol.
When the module is in UART mode (note that the host computer 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 wire sequence and power supply voltage), after successful recognition, click to enter the settings page, configure the parameters and then click the write parameters button to save the parameters. Note: After switching to IIC 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.
[!WARNING]
Before modifying the configuration, please remember your baud rate (Baudeate) before the configuration, so that you can 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 Result
I/O Output
In I/O output mode, it can only be used in single module mode, and the module cannot output ranging values. TX/CAN_L and RX/CAN_H output complementary levels, the two signal line levels are opposite, the high level is 3.3V, the low level is 0V, and it should be noted that the output current is small, when driving other devices, it should be noted whether it can drive, if it cannot drive directly, it can use relays and other ways to drive.
When the module is in UART mode (note that the host computer 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 wire sequence and power supply voltage), after successful recognition, click to enter the settings page, configure the parameters and then 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.
[!WARNING]
Before modifying the configuration, please remember your baud rate (Baudeate) before the configuration, so that you can 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 shown in figure 4, 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 threshold = 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, the IO double threshold configuration is shown in figure 5, 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 to 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 below the low threshold, the I/O port level is reversed.
For example, based on the above settings, the low threshold is 1 meter, 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 to more than 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 to less than 1 meter, the level is reversed, RX is high level, TX is low level.
Hysteresis comparison schematic diagram is as follows

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 recognizing modules in UART mode. In UART mode, you can configure the module as IIC or I/O communication mode by entering the settings page after successfully recognizing the module through the host computer; in IIC communication mode, you can switch back to UART or I/O mode by sending commands to the module through IIC communication according to the IIC communication protocol; in addition, you can switch back to UART mode by the following method without IIC test environment or after switching to I/O mode:
The user needs to prepare a USB to TTL module that supports a baud rate of 921600 (CP2102 is recommended) and install the corresponding driver program, connect the TX, RX, and 5V three wires of the USB to TTL module to the corresponding pins of the TOF module, and temporarily do not connect the GND pin, then plug the USB to TTL module into the computer.
Open the host computer software, click the
icon to enter the serial port debugging assistant, change the baud rate to the baud rate you set before (if you have not modified the baud rate, it is 921600), select the COM port corresponding to the USB to TTL module and then click the
connection button to connect to the COM port (in most cases, it will automatically connect), 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 single send text box, change the send interval to 20ms in the timed send bar at the bottom right, then check the timed send button.
Now 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, now uncheck the timed send button, then unplug the USB to TTL module and re-power up the module, click the
recognition button on the main page to recognize the module.
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.