Livox_mapping 中tf的timestamp不更新/错误更新

文章讲述了作者在使用Livox_mapping进行路径规划时遇到的odom与maptf无法更新的问题,原因是Livox_mapping中时间戳发布错误导致。通过将关键时间变量从float改为double类型,解决了这个问题,最终导航显示恢复正常。

项目场景:

笔者在使用Livox_mapping的点云地图做路径规划时,启动move_base发现odom(camera_init) 与map之间的tf无法正常更新,但tf_tree却显示两者之间正常连接。


问题描述

1. move_base报错,找不到 transform from frame [aft_mapped] to frame [map]

Extrapolation Error looking up robot pose: Lookup would require extrapolation 2.254647634s into the past.  Requested time 1693479424.000000000 but the earliest data is at time 1693479426.254647732, when looking up transform from frame [aft_mapped] to frame [map]

发现是aft_mapped和map没有即使更新,往前查Livox_mapping的原因。

2. Livox_mapping warning :  时间戳重复

 TF_REPEATED_DATA ignoring data with redundant timestamp for frame aft_mapped at time 1693537024.000000 according to authority unknown_publisher

 


原因分析:

根本原因是Livox_mapping中发布tf [aft_mapped] to frame [camera_init] 时时间戳更新错误,一直打的同一个时间戳。

在代码中每个timestamp调试后发现:

laserCloudCornerLast2 在赋值时前后出现了错误。

 

laserCloudCornerLast2 定义为float,在赋值出现了精度损失

 


解决方案:

// float timeLaserCloudCornerLast = 0;
// float timeLaserCloudSurfLast = 0;
// float timeLaserCloudFullRes = 0;
double timeLaserCloudCornerLast = 0;
double timeLaserCloudSurfLast = 0;
double timeLaserCloudFullRes = 0;

把float换成double

最后用Livox HAP 导航显示正常:

void Preprocess::hesai_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) { pl_surf.clear(); pl_corn.clear(); pl_full.clear(); pcl::PointCloud<hesai_ros::Point> pl_orig; pcl::fromROSMsg(*msg, pl_orig); int plsize = pl_orig.points.size(); if (plsize == 0) return; pl_surf.reserve(plsize); double begin_time = msg->header.stamp.toSec(); if(feature_enabled) { for (int i = 0; i < N_SCANS; i++) { pl_buff[i].clear(); pl_buff[i].reserve(plsize); } } for (int i = 0; i < plsize; i++) { PointType added_pt; added_pt.normal_x = 0; added_pt.normal_y = 0; added_pt.normal_z = 0; int layer = pl_orig.points[i].ring; if (layer >= N_SCANS) continue; added_pt.x = pl_orig.points[i].x; added_pt.y = pl_orig.points[i].y; added_pt.z = pl_orig.points[i].z; added_pt.intensity = pl_orig.points[i].intensity; added_pt.curvature = (pl_orig.points[i].timestamp - begin_time) * time_unit_scale; if(feature_enabled) { pl_buff[layer].points.push_back(added_pt); } else { if (i % point_filter_num == 0) { if(added_pt.x*added_pt.x+added_pt.y*added_pt.y+added_pt.z*added_pt.z > (blind * blind)) { pl_surf.points.push_back(added_pt); } } } } } 这是我fastlio2中处理雷达数据的函数,这是其中hesai_ros namespace hesai_ros { struct EIGEN_ALIGN16 Point { PCL_ADD_POINT4D; float intensity; double timestamp; uint16_t ring; EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } // namespace hesai_ros POINT_CLOUD_REGISTER_POINT_STRUCT(hesai_ros::Point, (float, x, x) (float, y, y) (float, z, z) (float, intensity, intensity) (double, timestamp, timestamp) (std::uint16_t, ring, ring) ) 下面是发出端的数据结构 struct PointXYZIT { PCL_ADD_POINT4D float intensity; double timestamp; uint16_t ring; EIGEN_MAKE_ALIGNED_OPERATOR_NEW } EIGEN_ALIGN16; POINT_CLOUD_REGISTER_POINT_STRUCT( PointXYZIT, (float, x, x) (float, y, y) (float, z, z) (float, intensity, intensity) (double, timestamp, timestamp) (std::uint16_t, ring, ring) ) 下面是雷达发布话题的情况 hao@hao-ubuntu:~/ROS_SDK_2.1.0_jt16_0120$ rostopic echo -n 1 /lidar_points/fields - name: "x" offset: 0 datatype: 7 count: 1 - name: "y" offset: 4 datatype: 7 count: 1 - name: "z" offset: 8 datatype: 7 count: 1 - name: "intensity" offset: 12 datatype: 7 count: 1 - name: "ring" offset: 16 datatype: 4 count: 1 --- hao@hao-ubuntu:~/ROS_SDK_2.1.0_jt16_0120$ rostopic echo -n 1 /lidar_points/header seq: 186 stamp: secs: 0 nsecs: 0 frame_id: "hesai_lidar" --- 两边哪里还匹配,会报错 hao@hao-ubuntu:~/livox$ roslaunch fast_lio mapping_hesai.launch ... logging to /home/hao/.ros/log/c5ff68e8-4750-11f0-aff3-5f57413891f7/roslaunch-hao-ubuntu-6731.log Checking log directory for disk usage. This may take a while. Press Ctrl-C to interrupt WARNING: disk usage in log directory [/home/hao/.ros/log] is over 1GB. It's recommended that you use the 'rosclean' command. started roslaunch server http://hao-ubuntu:40741/ SUMMARY ======== PARAMETERS * /common/imu_topic: /lidar_imu * /common/lid_topic: /lidar_points * /common/time_offset_lidar_to_imu: 0.0 * /common/time_sync_en: False * /cube_side_length: 1000.0 * /feature_extract_enable: False * /filter_size_map: 0.3 * /filter_size_surf: 0.3 * /mapping/acc_cov: 0.3 * /mapping/b_acc_cov: 0.001 * /mapping/b_gyr_cov: 0.001 * /mapping/det_range: 100.0 * /mapping/extrinsic_R: [0, -1, 0, -1, 0,... * /mapping/extrinsic_T: [-0.001, -0.00855... * /mapping/extrinsic_est_en: True * /mapping/fov_degree: 180 * /mapping/gyr_cov: 0.3 * /max_iteration: 5 * /pcd_save/interval: -1 * /pcd_save/pcd_save_en: False * /point_filter_num: 1 * /preprocess/blind: 0.5 * /preprocess/lidar_type: 4 * /preprocess/scan_line: 16 * /preprocess/scan_rate: 10 * /preprocess/timestamp_unit: 0 * /publish/dense_publish_en: True * /publish/path_en: True * /publish/scan_bodyframe_pub_en: True * /publish/scan_publish_en: True * /rosdistro: noetic * /rosversion: 1.17.0 * /runtime_pos_log_enable: False * /use_sim_time: False NODES / laserMapping (fast_lio/fastlio_mapping) orientation_fix (tf/static_transform_publisher) rviz (rviz/rviz) ROS_MASTER_URI=http://localhost:11311 process[laserMapping-1]: started with pid [6748] process[orientation_fix-2]: started with pid [6749] process[rviz-3]: started with pid [6750] Multi thread started p_pre->lidar_type 4 ~~~~/home/hao/livox/src/fast_lio_hesai/ file opened Failed to find match for field 'timestamp'. Failed to find match for field 'timestamp'. [ WARN] [1749707491.138653256]: No point, skip this scan__1!
06-13
/**: ros__parameters: locate_in_prior_map: false feature_extract_enable: false point_filter_num: 3 max_iteration: 3 filter_size_surf: 0.5 filter_size_map: 0.5 cube_side_length: 1000.0 runtime_pos_log_enable: false map_file_path: "./test.pcd" common: odom_frame_id: "odom" sensor_frame_id: "imu_link" base_frame_id: "base_link" send_odom_base_tf: true lid_topic: "/livox/lidar" imu_topic: "/imu/data" time_sync_en: false # ONLY turn on when external time synchronization is really not possible time_offset_lidar_to_imu: 0.0 # Time offset between lidar and IMU calibrated by other algorithms, e.g. LI-Init (can be found in README). # This param will take effect no matter what time_sync_en is. So if the time offset is not known exactly, please set as 0.0 preprocess: lidar_type: 1 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR, 4 for any other pointcloud input scan_line: 16 blind: 0.5 timestamp_unit: 3 scan_rate: 10 mapping: acc_cov: 0.1 gyr_cov: 0.1 b_acc_cov: 0.0001 b_gyr_cov: 0.0001 fov_degree: 360.0 det_range: 57.0 extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic extrinsic_T: [ -0.011, -0.02329, 0.04412 ] extrinsic_R: [ 1., 0., 0., 0., -1., 0., 0., 0., -1.] publish: path_en: true # true: publish Path effect_map_en: true # true: publish Effects map_en: true # true: publish Map cloud scan_publish_en: true # false: close all the point cloud output dense_publish_en: true # false: low down the points number in a global-frame point clouds scan. scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame pcd_save: pcd_save_en: true interval: -1 # how many LiDAR frames saved in each pcd file; # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames.
最新发布
11-06
在 ROS 1 Noetic 系统下,运行 `./livox_lidar_quick_start ../../../samples/livox_lidar_quick_start/mid360_config.json` 提示没有该文件或目录,可按以下方法解决: #### 检查当前目录 要确保已经正确进入 `livox_ws/3rd_party/Livox - SDK2/build/samples/livox_lidar_quick_start` 文件夹。可以使用以下命令查看当前所在目录: ```bash pwd ``` 若当前目录是预期的目录,使用 `cd` 命令进入正确目录: ```bash cd livox_ws/3rd_party/Livox - SDK2/build/samples/livox_lidar_quick_start ``` #### 检查可执行文件是否存在 确认 `livox_lidar_quick_start` 可执行文件是否存在于当前目录。使用以下命令查看: ```bash ls livox_lidar_quick_start ``` 若文件存在,可能是编译过程中出现问题,需要重新编译 Livox SDK2。 #### 检查配置文件路径 验证 `../../../samples/livox_lidar_quick_start/mid360_config.json` 路径是否正确。可以使用以下命令查看该文件是否存在: ```bash ls ../../../samples/livox_lidar_quick_start/mid360_config.json ``` 若文件存在,需要检查 Livox SDK2 是否正确安装,或者文件是否被误删除。 #### 检查文件权限 确保 `livox_lidar_quick_start` 具有可执行权限。若没有,使用以下命令添加执行权限: ```bash chmod +x livox_lidar_quick_start ``` #### 相对路径与绝对路径 如果相对路径仍然有问题,可以尝试使用绝对路径。使用以下命令获取 `mid360_config.json` 的绝对路径: ```bash realpath ../../../samples/livox_lidar_quick_start/mid360_config.json ``` 然后使用绝对路径运行命令: ```bash ./livox_lidar_quick_start /绝对路径/mid360_config.json ```
评论 1
成就一亿技术人!
拼手气红包6.0元
还能输入1000个字符
 
红包 添加红包
表情包 插入表情
 条评论被折叠 查看
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值