hku-mars / FAST_LIO

A computationally efficient and robust LiDAR-inertial odometry (LIO) package
GNU General Public License v2.0
2.79k stars 939 forks source link

When I placed the mid360 upside down, the localization of Fast LIO drifted away. #284

Closed 66Lau closed 1 year ago

66Lau commented 1 year ago

Hi! When I placed the mid360 upside down and modified the roll axis to 180 degrees in the Livox config file, the localization of Fast LIO drifted away. Did I miss some steps when I trying to place mid360 up side down?

Ecstasy-EC commented 1 year ago

What do you mean by "modified the roll axis to 180 degrees" in the config file?

66Lau commented 1 year ago

Sorry, for ambiguity, I mean I changed the extrinsic_parameter in MID360_config.json like the code below.

"lidar_configs" : [
    {
      "ip" : "192.168.1.12",
      "pcl_data_type" : 1,
      "pattern_mode" : 0,
      "extrinsic_parameter" : {
        "roll": 180,
        "pitch": 0.0,
        "yaw": 0.0,
        "x": 0,
        "y": 0,
        "z": 0
      }
    }
  ]

However, I found that this extrinsic_parameter can only change the pose of the pointclouds, but not IMU. As a result, the localization drifted away. When I try to use mid360 build the map in the tilted installation or inverted installation, the PCD looks very strange because it takes camera_init as the base coordinates. slope_down_37_degree

So I want to modify the code to map the imu in the inclined state to the horizontal state

I may have found a way to achieve this, just use static_transform_publisher to publish the transfrom from camera_init to foot_init if the installation of mid360 is not vertical and take the foot_init as the base coordinates 37_degree_adjust tftree But is not the routine method mentioned in navigationTutorialsRobotSetupTF that "we need a way of transforming the laser scan we've received from the "base_laser" frame to the "base_link" frame."

Is there any better way?

Ecstasy-EC commented 1 year ago

As we build the map in the IMU frame, I would suggest conducting a gravity alignment during the initialization step. Read the IMU to identify the gravity direction, and record a transformation matrix to translate your IMU to the gravity frame. After that, you only need to transform the point cloud via that matrix when publish the point clouds. You'll obtain the point cloud in the gravity frame by doing so.

66Lau commented 1 year ago

Make sense, appreciate!!

IacopomC commented 3 months ago

I know this issue is closed but I'm having the same issue and I was able to partially solve it. Basically, I left the extrinsic parameters in the config file of the Mid-360 (mid360.yaml) untouched, I changed the orientation of the livox point cloud in the ros driver itself (flipping it 180 degrees around the x axis) and I republished the IMU data also flipping it around the x axis 180 degrees. While the overall point cloud (or final map) is correctly reconstructed, the initial pose seems to jump from (0,0,0) all the way to a point of random coordinates very far from the (0,0,0). You can see that in the image below where the blue path seems to go all the way to infinity but that's actually how it starts as soon as I play the rosbag. Do you know how I could fix that?

fast_lio_init_pose

Ecstasy-EC commented 3 months ago

I know this issue is closed but I'm having the same issue and I was able to partially solve it. Basically, I left the extrinsic parameters in the config file of the Mid-360 (mid360.yaml) untouched, I changed the orientation of the livox point cloud in the ros driver itself (flipping it 180 degrees around the x axis) and I republished the IMU data also flipping it around the x axis 180 degrees. While the overall point cloud (or final map) is correctly reconstructed, the initial pose seems to jump from (0,0,0) all the way to a point of random coordinates very far from the (0,0,0). You can see that in the image below where the blue path seems to go all the way to infinity but that's actually how it starts as soon as I play the rosbag. Do you know how I could fix that?

fast_lio_init_pose

How do you obtain that point cloud with a jump position? The point cloud looks quite good indicating that the trajectory was also good.

IacopomC commented 3 months ago

I think just the initial Odometry guess is wrong because after that the rest of the Odometry is correct. I tried with a new rosbag and the system I described above (that you suggested) seems to work correctly. Thanks anyway!