Introduction
The TOF laser ranging sensor is a new generation of laser ranging sensor based on dTOF (Direct Time of Flight) technology. It has been comprehensively upgraded in terms of hardware design and algorithm, with a ranging blind area of less than 2cm, a maximum range of up to 7.8m (specifically depending on the reflectivity of the environment), and a ranging accuracy within ±4cm (typical value), especially stable performance in dynamic environments, and a resistance to environmental light interference of up to 100K LUX, suitable for indoor and outdoor strong light environments. It supports UART, I2C, I/O and other communication interfaces to meet different development architecture needs.
The TOF laser ranging sensor-7.8 highlights its ultra-small size (only 1g weight) and high cost performance, and is specifically 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 detection area with multiple sensors and combining high frame rate (up to 50Hz) data output, dynamic obstacle avoidance and path planning can be achieved
Drone Altitude Hold and Terrain Follow
Installed at the bottom of the drone, real-time measurement of the distance from the ground, assisting in precise altitude hold and landing, especially excellent performance 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 the production line
Smart Traffic and Traffic Flow Monitoring
Deployed on road gantries or parking lots, counting 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, realizing gesture recognition, motion monitoring and other interactive functions.
Product Parameters
- Refresh Rate: 50Hz
- Classic Ranging Range: 0.02~7.8m
- Classic Ranging Accuracy: ±4cm
- Wavelength: 940nm
- Anti-Environmental Light: 100K LUX Illumination
- Field of View (FOV): 2~3°
- Power Supply Voltage: 4.3V~5.2V
- Power Consumption: 100mW
- Communication Interface: UART/IIC/IO
- IIC Default Slave Address: 0x80
- Operating Temperature: -10℃~60℃
- Dimensions: 19.0 mm *12.0 mm *10.3mm
- Product Weight: 1g
Dimension Parameters

Usage Tutorial
Preparation
- Hardware
- TOF Laser Ranging Sensor-7.8 meters
- ESP32 Series Development Board
- Software
- Sensor Host Machine, click to download the host machine
- Arduino IDE, click to download Arduino IDE
Serial Output
UART mode has two output modes: Active Output and Query Output, which can be switched by modifying the data output mode on the host machine software. Connect the TOFSense-F/F2 series products to the host machine software through the USB to TTL module (refer to the data manual for line sequence and power supply voltage), after successful identification, click to enter the setting page, configure the parameters and click the write parameter button to save the parameters, after writing the parameters successfully, 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.
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 outputs measurement information actively at a default 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 TOF module
unsigned long system_time; //The time elapsed after the TOF module is powered on, unit: ms
float dis; //The distance output by the TOF module, unit: m
unsigned char dis_status; //Distance status indicator output by the TOF module
unsigned int signal_strength; //Signal strength output by the TOF module
unsigned char range_precision; //Reference value of repeated ranging accuracy output by the TOF module, valid for TOFSense-F series, unit: cm
} tof_parameter; //Data structure after decoding TOF data
/**
@brief Read data from the serial port
@param buf Stores the read data
@param len The 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 Stores 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 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 after 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 indicator 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 the repeated 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 mode 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 reported actively. 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 TOF module
unsigned long system_time; //The time elapsed after the TOF module is powered on, unit: ms
float dis; //The distance output by the TOF module, unit: m
unsigned char dis_status; //Distance status indicator output by the TOF module
unsigned int signal_strength; //Signal strength output by the TOF module
unsigned char range_precision; //Reference value of repeated ranging accuracy output by the TOF module, valid for TOFSense-F series, unit: cm
} tof_parameter; //Data structure after decoding TOF data
/**
@brief Read data from the serial port
@param buf Stores the read data
@param len The 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 Stores 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 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 after 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 indicator 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 the repeated ranging accuracy output by the TOF module
ret = true;
}
}
}
}
}
}
}
return ret;
}
Output Results

IIC Output
IIC mode can be used in single module and cascade. 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 module's output mode and other parameters through IIC communication. The read frame and write frame formats follow the NLink_TOFSense_IIC_Frame0 protocol.
When the module is in UART mode (note that the host machine cannot recognize the module in IIC mode), connect the TOFSense series products to the host machine software through the USB to TTL module (refer to the data manual for line sequence and power supply voltage), after successful identification, click to enter the setting page, IIC output mode configuration is as shown in the figure, you can change the IIC slave address of the module by setting the module's ID (7-bit slave address is 0x08+module ID, ID setting range is 0~111), after configuring the parameters, you need to click the write parameter 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 way in the FAQ section to change back to UART mode for configuration.
[!WARNING]
Please remember your baud rate (Baudeate) before modifying 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 indicator
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 level, the level state of the two signal lines is opposite, high level is 3.3V, low level is 0V, in addition, 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 be driven by relays and other ways.
When the module is in UART mode (note that the host machine cannot recognize the module in I/O mode), connect the TOFSense series products to the host machine software through the USB to TTL module (refer to the data manual for line sequence and power supply voltage), after successful identification, click to enter the setting page, configure the parameters and click the write parameter 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 way in the FAQ section to change back to UART mode for configuration.
[!WARNING]
Please remember your baud rate (Baudeate) before modifying 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 as shown in the figure, after writing the parameters, the module will restart and no longer output ranging value but output high and low level.
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 as shown in the figure, after writing the parameters, the module will restart and no longer output ranging value but output high and low level.

According to the above settings, this mode converts the distance value 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, 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 shown in the figure

Frequently Asked Questions
Why can't the host machine software recognize the module after switching to IIC or I/O mode? How to switch between different communication modes?
Currently, the host machine software only supports the recognition of modules in UART mode. In UART mode, you can configure the module as IIC or I/O communication mode by entering the setting page after successfully recognizing the module on the host machine; 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 in the following ways without IIC test environment or after switching to I/O mode:
Users need 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 do not connect the GND pin for the time being. Then plug the USB to TTL module into the computer.
Open the host machine software, click
icon 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
connect button to connect the COM port (in most cases, it will connect automatically), 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, and then check timed send.
At this point, 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 point uncheck the timed send button, then unplug the USB to TTL module and repower the module, then click the
identify button on the main page to identify the module.
If the switch fails, unplug the USB to TTL module and repeat the whole process. Do not unplug and plug the GND pin multiple times while sending commands. If the module can be recognized normally but the serial port output data is abnormal, you can manually change to UART mode in the setting page.