koide3 / glim

GLIM: versatile and extensible range-based 3D localization and mapping framework
MIT License
441 stars 55 forks source link

Problem play rosbag2 from Mid-360 #66

Closed GeomPozzoli closed 2 weeks ago

GeomPozzoli commented 3 weeks ago

hello koide3, I'm trying to use glim with a livox mid 360 but I can't figure out where I'm going wrong. I tried to record rosbag2 through livox_ros_driver2 in ros2 environment with xfer_format 1 (livox custumized pointcloud) but when I launch glim the process stops, while with xfer_format 2 (Livox pointcloud2 PointXYZRTLT) the following warning is reported:

[2024-08-22 12:55:42.578] [glim] [info] opening rosbag2_2024_08_22-11_41_43
[INFO] [1724331342.583763882] [rosbag2_storage]: Opened database 'rosbag2_2024_08_22-11_41_43/rosbag2_2024_08_22-11_41_43_0.db3' for READ_ONLY.
[2024-08-22 12:55:42.589] [glim] [warning] large point timestamp (min=1724319703997192448.000000 max=1724319704093192448.000000 > 1.0) found!!
[2024-08-22 12:55:42.589] [glim] [warning] assume that point times are absolute and convert them to relative
[2024-08-22 12:55:42.589] [glim] [warning] too large point timestamp (min=1724319703997192448.000000 max=1724319704093192448.000000 > 1e16) found!!
[2024-08-22 12:55:42.589] [glim] [warning] maybe using a Livox LiDAR that use FLOAT64 nanosec per-point timestamps
[2024-08-22 12:55:42.589] [glim] [warning] frame timestamp will be overwritten by the first point timestamp!!
[2024-08-22 12:55:42.867] [glim] [warning] large time gap between consecutive IMU data!!
[2024-08-22 12:55:42.867] [glim] [warning] current=1724319704.835668 last=1724319704.595483 diff=0.240185
[2024-08-22 12:55:43.130] [glim] [warning] large time gap between consecutive IMU data!!
[2024-08-22 12:55:43.130] [glim] [warning] current=1724319705.645626 last=1724319705.255618 diff=0.390008
[2024-08-22 12:55:43.503] [glim] [warning] large time gap between consecutive IMU data!!
[2024-08-22 12:55:43.503] [glim] [warning] current=1724319706.255457 last=1724319705.995660 diff=0.259798
[2024-08-22 12:55:43.850] [glim] [warning] large time gap between consecutive IMU data!!
[2024-08-22 12:55:43.850] [glim] [warning] current=1724319706.979836 last=1724319706.695626 diff=0.284211
[2024-08-22 12:55:44.159] [glim] [warning] large time gap between consecutive IMU data!!
[2024-08-22 12:55:44.159] [glim] [warning] current=1724319707.650025 last=1724319707.395625 diff=0.254400
[2024-08-22 12:55:44.518] [odom] [info] estimate initial IMU state
Initial error: 88.1372, values: 96
iter      cost      cost_change    lambda  success iter_time
   0  4.340022e-02    8.81e+01    1.00e-05     1    2.67e-03
   1  4.189407e-02    1.51e-03    1.00e-06     1    2.29e-03
   2  4.189407e-02   -2.35e-13    1.00e-07     1    3.92e-03
[2024-08-22 12:55:44.532] [odom] [info] initial IMU state estimation result
[2024-08-22 12:55:44.532] [odom] [info] T_world_imu=se3(0.000078,-0.000299,-0.000410,0.000799,0.001389,-0.004780,0.999987)
[2024-08-22 12:55:44.533] [odom] [info] v_world_imu=vec(0.002814,-0.003181,-0.022666)
[2024-08-22 12:55:44.533] [odom] [info] imu_bias=vec(0.000304,-0.000161,-0.000621,0.000526,-0.000713,-0.001706)
[2024-08-22 12:55:44.580] [glim] [warning] large time gap between consecutive IMU data!!
[2024-08-22 12:55:44.580] [glim] [warning] current=1724319708.375599 last=1724319708.089804 diff=0.285795
[2024-08-22 12:55:44.673] [odom] [warning] insufficient number of IMU data between LiDAR scans!! (odometry_estimation)
[2024-08-22 12:55:44.673] [odom] [warning] t_last=1724319707.393136 t_current=1724319707.493048 num_imu=1
[2024-08-22 12:55:44.705] [odom] [warning] insufficient number of IMU data between LiDAR scans!! (odometry_estimation)
[2024-08-22 12:55:44.705] [odom] [warning] t_last=1724319707.493048 t_current=1724319707.593107 num_imu=0
[2024-08-22 12:55:44.904] [odom] [warning] insufficient number of IMU data between LiDAR scans!! (odometry_estimation)
[2024-08-22 12:55:44.904] [odom] [warning] t_last=1724319708.093061 t_current=1724319708.193122 num_imu=0
[2024-08-22 12:55:44.906] [glim] [warning] large time gap between consecutive IMU data!!
..........
[2024-08-22 12:55:53.095] [glim] [warning] current=1724319725.169971 last=1724319724.895814 diff=0.274157
[2024-08-22 12:55:53.155] [submap] [warning] insufficient IMU data between LiDAR frames!! (sub_mapping)
[2024-08-22 12:55:53.278] [submap] [warning] insufficient IMU data between LiDAR frames!! (sub_mapping)[2024-08-22 12:55:53.423] [odom] [warning] insufficient number of IMU data between LiDAR scans!! (odometry_estimation)
[2024-08-22 12:55:53.423] [odom] [warning] t_last=1724319724.893174 t_current=1724319724.993114 num_imu=1
[2024-08-22 12:55:53.487] [odom] [warning] insufficient number of IMU data between LiDAR scans!! (odometry_estimation)
[2024-08-22 12:55:53.487] [odom] [warning] t_last=1724319724.993114 t_current=1724319725.093210 num_imu=0
[2024-08-22 12:55:53.601] [submap] [warning] insufficient IMU data between LiDAR frames!! (sub_mapping)

After kill the process with CTRL+C

 [1724331393.374470928] [rclcpp]: signal_handler(signum=2)

>>> [rcutils|error_handling.c:108] rcutils_set_error_state()
This error state is being overwritten:

  'Handle's typesupport identifier (rosidl_typesupport_cpp) is not supported by this library, at ./src/type_support_dispatch.hpp:111'

with this new error message:

  'publisher's context is invalid, at ./src/rcl/publisher.c:389'

rcutils_reset_error() should be called after error handling to avoid this.
<<<
[2024-08-22 12:56:33.375] [glim] [info] waiting for odometry estimation
[2024-08-22 12:56:33.376] [glim] [info] waiting for local mapping
[2024-08-22 12:56:33.386] [submap] [warning] insufficient IMU data between LiDAR frames!! (sub_mapping)
[2024-08-22 12:56:33.387] [submap] [warning] insufficient IMU data between LiDAR frames!! (sub_mapping)
[2024-08-22 12:56:33.400] [submap] [warning] insufficient IMU data between LiDAR frames!! (sub_mapping)
[2024-08-22 12:56:33.401] [submap] [warning] insufficient IMU data between LiDAR frames!! (sub_mapping)
[2024-08-22 12:56:33.414] [submap] [warning] insufficient IMU data between LiDAR frames!! (sub_mapping)
[2024-08-22 12:56:33.415] [submap] [warning] insufficient IMU data between LiDAR frames!! (sub_mapping)
[2024-08-22 12:56:33.427] [submap] [warning] insufficient IMU data between LiDAR frames!! (sub_mapping)
[2024-08-22 12:56:33.428] [submap] [warning] insufficient IMU data between LiDAR frames!! (sub_mapping)
[2024-08-22 12:56:33.440] [submap] [warning] insufficient IMU data between LiDAR frames!! (sub_mapping)
[2024-08-22 12:56:33.442] [submap] [warning] insufficient IMU data between LiDAR frames!! (sub_mapping)
[2024-08-22 12:56:33.453] [submap] [warning] insufficient IMU data between LiDAR frames!! (sub_mapping)
[2024-08-22 12:56:33.454] [submap] [warning] insufficient IMU data between LiDAR frames!! (sub_mapping)
[2024-08-22 12:56:33.467] [submap] [warning] insufficient IMU data between LiDAR frames!! (sub_mapping)
[2024-08-22 12:56:33.469] [submap] [warning] insufficient IMU data between LiDAR frames!! (sub_mapping)
[2024-08-22 12:56:33.486] [glim] [info] waiting for global mapping
[2024-08-22 12:56:33.502] [global] [info] saving to /tmp/dump...
[2024-08-22 12:56:33.503] [global] [info] serializing factor graph to /tmp/dump/graph.bin
[2024-08-22 12:56:33.680] [global] [info] saved

I can't understand if the problem is in the acquisition data or in the configuration I made in GLIM, I have modified acc_scale, imu_topics, lidar_topics, T_lidar_imu, autoconf_perpoint_times: true, autoconf_prefer_frame_time: true

Did I miss any other strictly necessary changes?

Sorry for the stupid questions but I'm new to ROS and SLAM

Good Day

koide3 commented 2 weeks ago

I confirmed that GLIM works well with rviz_MID360_launch.py in livox_ros_driver2 with minor modifications described in the sensor setup guide.

Besides the configuration of GLIM, a common pitfall is ROS2 bag recording. You can quickly check if messages were properly recorded with ros2 bag info. If things went correctly, there should be about x10 and x200 amount of points and IMU messages with respect to the bag duration like the following example.

Files:             rosbag2_2024_04_16-14_17_01_0.db3
Bag size:          1.4 GiB
Storage id:        sqlite3
ROS Distro:        unknown
Duration:          277.166s
Start:             Apr 16 2024 14:17:01.183 (1713244621.183)
End:               Apr 16 2024 14:21:38.350 (1713244898.350)
Messages:          58217
Topic information: Topic: /livox/imu | Type: sensor_msgs/msg/Imu | Count: 55435 | Serialization Format: cdr
                   Topic: /livox/lidar | Type: sensor_msgs/msg/PointCloud2 | Count: 2772 | Serialization Format: cdr
Service:           0
Service information: 
GeomPozzoli commented 2 weeks ago

thanks for the reply, actually the IMU data is at 122x and not 200x

Files:             rosbag2_2024_08_22-11_41_43_0.db3
Bag size:          108.5 MiB
Storage id:        sqlite3
Duration:          21.534674116s
Start:             Aug 22 2024 09:41:44.066534535 (1724319704.066534535)
End:               Aug 22 2024 09:42:05.601208651 (1724319725.601208651)
Messages:          2844
Topic information: Topic: /livox/imu | Type: sensor_msgs/msg/Imu | Count: 2628 | Serialization Format: cdr
                   Topic: /livox/lidar | Type: sensor_msgs/msg/PointCloud2 | Count: 216 | Serialization Format: cdr
                   Topic: /parameter_events | Type: rcl_interfaces/msg/ParameterEvent | Count: 0 | Serialization Format: cdr
                   Topic: /rosout | Type: rcl_interfaces/msg/Log | Count: 0 | Serialization Format: cdr

I'll try to make some other registrations and see if I can solve it

GeomPozzoli commented 2 weeks ago

After several tests I was able to verify that recording through ROS2 always gives me problems (at least on the raspberry pi4 4Gb). Instead, by proceeding with recording with ROS Noetic and then converting the .bag to ROS2, there are no more errors on the imu.