Make VL6180x less noisy
This commit is contained in:
parent
3681e11354
commit
aaa59c29a9
|
@ -33,6 +33,9 @@ void RideheightSensing::spin() {
|
|||
vl6180x_msg.header.stamp = ros::Time::now();
|
||||
vl6180x_msg.range = vl6180x_range.range_mm / 1000.0f;
|
||||
vl6180x_pub.publish(vl6180x_msg);
|
||||
} else {
|
||||
ROS_WARN("VL6180X Ranging error: %s",
|
||||
VL6180x_RangeGetStatusErrString(vl6180x_range.errorStatus));
|
||||
}
|
||||
ros::spinOnce();
|
||||
loop_rate.sleep();
|
||||
|
|
|
@ -35,7 +35,6 @@ extern "C" {
|
|||
int VL6180x_I2CWrite(VL6180xDev_t dev, uint8_t *buff, uint8_t len) {
|
||||
int ret = write(i2c_dev_file, buff, len);
|
||||
if (ret == len) {
|
||||
ROS_INFO("Successfully wrote to I2C device");
|
||||
return 0;
|
||||
} else if (ret < 0) {
|
||||
ROS_ERROR("Error while writing to I2C device: %s", strerror(errno));
|
||||
|
|
Loading…
Reference in New Issue