diff --git a/src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c.cpp b/src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c.cpp index e0e4cc785a..3e7d1d5ea4 100644 --- a/src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c.cpp +++ b/src/drivers/distance_sensor/tfmini_i2c/tfmini_i2c.cpp @@ -315,6 +315,8 @@ TFMINI_I2C::set_param() { int ret; +// const uint8_t CMD_SYSTEM_RESET[] = { 0x5A , 0x05 , 0x0B , 0x20 , 0x8a }; // 修改地址 +// const uint8_t CMD_OUTPUT_FORMAT_CM[] = { 0x5A, 0x04, 0x11, 0x6F }; // 保存配置 const uint8_t CMD_SYSTEM_RESET[] = { 0x5A, 0x04, 0x04, 0x62 }; const uint8_t CMD_OUTPUT_FORMAT_CM[] = { 0x5A, 0x05, 0x05, 0x01, 0x65 }; const uint8_t CMD_ENABLE_DATA_OUTPUT[] = { 0x5A, 0x05, 0x07, 0x01, 0x67 }; @@ -387,7 +389,7 @@ TFMINI_I2C::collect() if (ret_val < 0) { - PX4_ERR("sensor %i read failed, address: 0x%02X", _sensor_index, get_device_address()); + // PX4_ERR("sensor %i read failed, address: 0x%02X", _sensor_index, get_device_address()); perf_count(_comms_error); perf_end(_sample_perf); // if (measure() != PX4_OK) { @@ -479,6 +481,13 @@ TFMINI_I2C::collect() // } + // static double dist_arr[6]={0.01,0.01,0.01,0.01,0.01,0.01}; + // dist_arr[_sensor_index] = (double)distance_m; + // if(hrt_absolute_time() - last_us > 100 * 1_ms){ + // printf("dist:%.2f,%.2f,%.2f,%.2f,%.2f,%.2f\n",dist_arr[0],dist_arr[1],dist_arr[2],dist_arr[3],dist_arr[4],dist_arr[5]); + // last_us = hrt_absolute_time(); + // } + perf_end(_sample_perf); return PX4_OK; } @@ -563,6 +572,8 @@ TFMINI_I2C::RunImpl() // Collect the sensor data. if (collect() != PX4_OK) { PX4_INFO("collection error"); + px4_usleep(1_s); + } }