TixiaoShan / LIO-SAM

LIO-SAM: Tightly-coupled Lidar Inertial Odometry via Smoothing and Mapping
BSD 3-Clause "New" or "Revised" License
3.5k stars 1.27k forks source link

with gps fator, the map optimization node crashed when encountering a big loop #301

Closed JokerJohn closed 2 years ago

JokerJohn commented 2 years ago

Thanks for your hard work! I run LIO-SAM with my own dataset, the sensors are velodyne 16, steam 300 and F9P GPS.

when the scene is very small(small loop) or the trajectory distance is very short, the LIO-SAM system runs well with GPS.

But when encountering a big closed loop, the mapOptimization node died and the lio_sam_udi_imuPreintegration process restart.how can i solve this problem?

I was confused by this problem for several weeks and it made me really frustrated. I would be grateful if anyone could help me

I recorded a vedio : vedio

image

ERROR:

Thrown when a linear system is ill-posed.  The most common cause for this
error is having underconstrained variables.  Mathematically, the system is
underdetermined.  See the GTSAM Doxygen documentation at
http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for
more information.
[lio_sam_udi_imuPreintegration-1] process has died [pid 4210, exit code -6, cmd /home/xchu/udicreator_ws/devel/lib/lio_sam_udi/lio_sam_udi_imuPreintegration __name:=lio_sam_udi_imuPreintegration __log:=/home/xchu/.ros/log/b1e2ffcc-63d9-11ec-8731-1065304bd5b6/lio_sam_udi_imuPreintegration-1.log].
log file: /home/xchu/.ros/log/b1e2ffcc-63d9-11ec-8731-1065304bd5b6/lio_sam_udi_imuPreintegration-1*.log
[lio_sam_udi_imuPreintegration-1] restarting process
process[lio_sam_udi_imuPreintegration-1]: started with pid [4240]
[ INFO] [1640275367.369310875]: ----> IMU Preintegration Started.
system initialization. 
currlidar pose: 17.2032814025879, -30.5312538146973, -48.5863075256348
currGPS position: 13.8068151473999, 7.92838048934937, 5.14798021316528
currGPS cov: 11.0224, 11.0224, 176.3584
terminate called after throwing an instance of 'gtsam::IndeterminantLinearSystemException'
  what():  
Indeterminant linear system detected while working near variable
7061644215716937728 (Symbol: b0).

Thrown when a linear system is ill-posed.  The most common cause for this
error is having underconstrained variables.  Mathematically, the system is
underdetermined.  See the GTSAM Doxygen documentation at
http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for
more information.
[lio_sam_udi_imuPreintegration-1] process has died [pid 4240, exit code -6, cmd /home/xchu/udicreator_ws/devel/lib/lio_sam_udi/lio_sam_udi_imuPreintegration __name:=lio_sam_udi_imuPreintegration __log:=/home/xchu/.ros/log/b1e2ffcc-63d9-11ec-8731-1065304bd5b6/lio_sam_udi_imuPreintegration-1.log].
log file: /home/xchu/.ros/log/b1e2ffcc-63d9-11ec-8731-1065304bd5b6/lio_sam_udi_imuPreintegration-1*.log
[lio_sam_udi_imuPreintegration-1] restarting process
process[lio_sam_udi_imuPreintegration-1]: started with pid [4268]
[ INFO] [1640275367.905634176]: ----> IMU Preintegration Started.
currlidar pose: 16.9986457824707, -29.6455020904541, -48.5315475463867
currGPS position: 13.9584197998047, 8.71054935455322, 4.71397876739502
currGPS cov: 11.0224, 11.0224, 176.3584
system initialization. 
terminate called after throwing an instance of 'gtsam::IndeterminantLinearSystemException'
  what():  
Indeterminant linear system detected while working near variable
7061644215716937728 (Symbol: b0).

Thrown when a linear system is ill-posed.  The most common cause for this
error is having underconstrained variables.  Mathematically, the system is
underdetermined.  See the GTSAM Doxygen documentation at
http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for
more information.
[lio_sam_udi_imuPreintegration-1] process has died [pid 4268, exit code -6, cmd /home/xchu/udicreator_ws/devel/lib/lio_sam_udi/lio_sam_udi_imuPreintegration __name:=lio_sam_udi_imuPreintegration __log:=/home/xchu/.ros/log/b1e2ffcc-63d9-11ec-8731-1065304bd5b6/lio_sam_udi_imuPreintegration-1.log].
log file: /home/xchu/.ros/log/b1e2ffcc-63d9-11ec-8731-1065304bd5b6/lio_sam_udi_imuPreintegration-1*.log
[lio_sam_udi_imuPreintegration-1] restarting process
process[lio_sam_udi_imuPreintegration-1]: started with pid [4310]
[ INFO] [1640275368.605006835]: ----> IMU Preintegration Started.
system initialization. 
currlidar pose: 16.4861240386963, -28.6083831787109, -48.5112152099609
currGPS position: 13.9197864532471, 9.7651309967041, 4.2459774017334
currGPS cov: 11.0224, 11.0224, 176.3584
terminate called after throwing an instance of 'gtsam::IndeterminantLinearSystemException'
  what():  
Indeterminant linear system detected while working near variable
7061644215716937728 (Symbol: b0).

Thrown when a linear system is ill-posed.  The most common cause for this
error is having underconstrained variables.  Mathematically, the system is
underdetermined.  See the GTSAM Doxygen documentation at
http://borg.cc.gatech.edu/ on gtsam::IndeterminantLinearSystemException for
more information.
[lio_sam_udi_imuPreintegration-1] process has died [pid 4310, exit code -6, cmd /home/xchu/udicreator_ws/devel/lib/lio_sam_udi/lio_sam_udi_imuPreintegration __name:=lio_sam_udi_imuPreintegration __log:=/home/xchu/.ros/log/b1e2ffcc-63d9-11ec-8731-1065304bd5b6/lio_sam_udi_imuPreintegration-1.log].
log file: /home/xchu/.ros/log/b1e2ffcc-63d9-11ec-8731-1065304bd5b6/lio_sam_udi_imuPreintegration-1*.log
JokerJohn commented 2 years ago

it is a campus dataset with huge elevation changes(mountains). The total distance of it is about 10-15km. The gps data of it is not very well, especially in the beginning 50 frames(NAN).

data path: mountain_campus

path:        hkust_20201105full_correct2.bag
version:     2.0
duration:    28:19s (1699s)
start:       Nov 05 2020 14:50:04.53 (1604559004.53)
end:         Nov 05 2020 15:18:24.35 (1604560704.35)
size:        13.2 GB
messages:    229287
compression: none [14808/14808 chunks]
types:       geometry_msgs/TwistStamped  [98d34b0043a2093cf9d9345ab6eef12e]
             sensor_msgs/CompressedImage [8f7a12909da2c9d3332d540a0977563f]
             sensor_msgs/Imu             [6a62c6daae103f4ff57a132d6f95cec2]
             sensor_msgs/NavSatFix       [2d3a8cd499b9b4a0249fb98fd05cfa48]
             sensor_msgs/PointCloud2     [1158d486dd51d683ce2f1be655c3c181]
             sensor_msgs/TimeReference   [fded64a0265108ba86c3d38fb11c0c16]
topics:      /fix                                    8494 msgs    : sensor_msgs/NavSatFix      
             /imu/data                             169972 msgs    : sensor_msgs/Imu            
             /stereo/left/image_color/compressed    16998 msgs    : sensor_msgs/CompressedImage
             /time_reference                         8494 msgs    : sensor_msgs/TimeReference  
             /vel                                    8357 msgs    : geometry_msgs/TwistStamped 
             /velodyne_points                       16972 msgs    : sensor_msgs/PointCloud2
JokerJohn commented 2 years ago

my yaml file:

lio_sam_udi:

  # Topics
  pointCloudTopic: "/velodyne_points"                  #"points_raw"               # Point cloud data
  imuTopic: "/imu/data"                  #"imu_raw"                         # IMU data
  odomTopic: "odometry/imu"                   # IMU pre-preintegration odometry, same frequency as IMU
  gpsTopic: "gps_odom"

  use_localmap: 0  # 1 true 使用点云地图原点, 否则使用车辆运动的起点作为地图原点

  # Frames
  lidarFrame: "base_link"
  baselinkFrame: "base_link"
  odometryFrame: "odom"
  mapFrame: "map"

  # GPS Settings
  useGPS: true
  useImuHeadingInitialization: false          # if using GPS data, set to "true"
  useGpsElevation: true                      # if GPS elevation is bad, set to "false"
  gpsCovThreshold: 12.98                        # m^2, threshold for using GPS data
  poseCovThreshold: 12.98                      # m^2, threshold for using GPS data

  # Export settings
  savePCD: true                              # https://github.com/TixiaoShan/LIO-SAM/issues/3
  savePCDDirectory: "/home/xchu/xchujwu_slam/liosam_data/"        # in your home folder, starts and ends with "/". Warning: the code deletes "LOAM" folder then recreates it. See "mapOptimization" for implementation

  # Sensor Settings
  sensor: "velodyne"                      # lidar sensor type, either 'velodyne' or 'ouster' or 'hesai'
  N_SCAN: 16                                  # number of lidar channel (i.e., 16, 32, 64, 128)
  Horizon_SCAN: 1800                          # lidar horizontal resolution (Velodyne:1800, Ouster:512,1024,2048)
  downsampleRate: 1                           # default: 1. Downsample your data if too many points. i.e., 16 = 64 / 4, 16 = 16 / 1
  lidarMinRange: 1.5                          # default: 1.0, minimum lidar range to be used
  lidarMaxRange: 80.0                       # default: 1000.0, maximum lidar range to be used

  # IMU Settings
  imuFrequence: 100
  imuAccNoise: 3.9939570888238808e-03
  imuGyrNoise: 1.5636343949698187e-03
  imuAccBiasN: 6.4356659353532566e-05
  imuGyrBiasN: 3.5640318696367613e-05
  imuGravity: 9.80511
  imuRPYWeight: 0.01

  # Extrinsics (lidar -> IMU)
  extrinsicTrans: [ 0.0, 0.0, -0.06 ]
  extrinsicRot: [ 1, 0, 0,
                  0, 1, 0,
                  0, 0, 1 ]
  extrinsicRPY: [ 1, 0, 0,
                  0, 1, 0,
                  0, 0, 1 ]

  # LOAM feature threshold
  edgeThreshold: 1.0
  surfThreshold: 0.1
  edgeFeatureMinValidNum: 10
  surfFeatureMinValidNum: 100

  # voxel filter paprams
  odometrySurfLeafSize: 0.4                     # default: 0.4 - outdoor, 0.2 - indoor
  mappingCornerLeafSize: 0.2                    # default: 0.2 - outdoor, 0.1 - indoor
  mappingSurfLeafSize: 0.4                      # default: 0.4 - outdoor, 0.2 - indoor

  # robot motion constraint (in case you are using a 2D robot)
  z_tollerance: 1000                            # meters
  rotation_tollerance: 1000                     # radians

  # CPU Params
  numberOfCores: 12                              # number of cores for mapping optimization
  mappingProcessInterval: 0.10                  # seconds, regulate mapping frequency

  # Surrounding map
  surroundingkeyframeAddingDistThreshold: 2.0   # meters, regulate keyframe adding threshold
  surroundingkeyframeAddingAngleThreshold: 0.2  # radians, regulate keyframe adding threshold
  surroundingKeyframeDensity: 2.0               # meters, downsample surrounding keyframe poses   
  surroundingKeyframeSearchRadius: 30.0         # meters, within n meters scan-to-map optimization (when loop closure disabled)

  # Loop closure
  loopClosureEnableFlag: true
  loopClosureFrequency: 1.0                     # Hz, regulate loop closure constraint add frequency
  surroundingKeyframeSize: 30                   # submap size (when loop closure enabled)
  historyKeyframeSearchRadius: 30.0             # meters, key frame that is within n meters from current pose will be considerd for loop closure
  historyKeyframeSearchTimeDiff: 30.0           # seconds, key frame that is n seconds older will be considered for loop closure
  historyKeyframeSearchNum: 20                  # number of hostory key frames will be fused into a submap for loop closure
  historyKeyframeFitnessScore: 0.8             # icp threshold, the smaller the better alignment
  loop_method: 1
  registeration_type: 0                        # 0 icp 1 ndt_omp

  scDistThres: 0.4
  scMaximumRadius: 60

  # Visualization
  globalMapVisualizationSearchRadius: 1500.0    # meters, global map visualization radius
  globalMapVisualizationPoseDensity: 2.0       # meters, global map visualization keyframe density
  globalMapVisualizationLeafSize: 1.0           # meters, global map visualization cloud density
JokerJohn commented 2 years ago

I did not use the ekf gps node in the robot_localization package and wrote my own gps odometry node and use it in the updateInitialGuess() to align the GPS Coordinate with the LiO-system.

I add some codes in the first key frame.

  if (cloudKeyPoses3D->points.empty()) {
      std::cout << "[mapOptmization3]: Ignore first key frame: " << cloudInfo.imuAvailable << ", "
                << cloudInfo.odomAvailable << std::endl;

      if (useGPS) {
        gpsAvialble = false;
        while (!gpsQueue.empty()) {
          mutex_lock.lock();
          double off_time = timeLaserInfoCur - gpsQueue.front().header.stamp.toSec();
          if (off_time > 0.5) {
            gpsQueue.pop_front();
            mutex_lock.unlock();
          } else if (off_time < -0.5) {
            // ROS_ERROR("failed to algned gps and lidar time, %f", off_time);
            mutex_lock.unlock();
            break;
          } else {
            nav_msgs::Odometry msg = gpsQueue.front();
            gpsQueue.pop_front();
            mutex_lock.unlock();
            ROS_WARN(" gps lidar off time: %f ", off_time);

            double roll, pitch, yaw;
            tf::Matrix3x3(tf::Quaternion(msg.pose.pose.orientation.x,
                                         msg.pose.pose.orientation.y,
                                         msg.pose.pose.orientation.z,
                                         msg.pose.pose.orientation.w)).getRPY(roll, pitch, yaw);
            std::cout << "rpy: " << roll << "," << pitch << ", " << yaw << std::endl;

            if (!std::isnan(yaw)) {
              transGPS.setIdentity();
              transGPS = pcl::getTransformation(msg.pose.pose.position.x,
                                                msg.pose.pose.position.y,
                                                msg.pose.pose.position.z,
                                                roll,
                                                pitch,
                                                yaw);

             // save origin GPS LLA data
              transLLA.setIdentity();
              transLLA = Eigen::Vector3d(msg.pose.covariance[1], msg.pose.covariance[2], msg.pose.covariance[3]);
              gpsAvialble = true;

              Eigen::AngleAxisd rollAngle1(roll, Eigen::Vector3d::UnitX());
              Eigen::AngleAxisd pitchAngle1(pitch, Eigen::Vector3d::UnitY());
              Eigen::AngleAxisd yawAngle1(yaw, Eigen::Vector3d::UnitZ());
              Eigen::Quaterniond q_gps = yawAngle1 * pitchAngle1 * rollAngle1;

              Eigen::AngleAxisd rollAngle(cloudInfo.imuRollInit, Eigen::Vector3d::UnitX());
              Eigen::AngleAxisd pitchAngle(cloudInfo.imuPitchInit, Eigen::Vector3d::UnitY());
              Eigen::AngleAxisd yawAngle(cloudInfo.imuYawInit, Eigen::Vector3d::UnitZ());
              Eigen::Quaterniond q_imu = yawAngle * pitchAngle * rollAngle;

              Eigen::Matrix3d rotation_matrix_imu = q_imu.toRotationMatrix();
              Eigen::Matrix3d rotation_matrix_gps = q_gps.toRotationMatrix();
              std::cout << "gps LLA: " << std::setprecision(15) << transLLA.matrix() << std::endl;

              Eigen::Matrix3d transIMUAft = rotation_matrix_gps.inverse() * rotation_matrix_imu;
              Eigen::Vector3d eulerAngle2 = transIMUAft.eulerAngles(0, 1, 2); // roll,pitch,yaw
              transformTobeMapped[0] = eulerAngle2[0];
              transformTobeMapped[1] = eulerAngle2[1];
              transformTobeMapped[2] = eulerAngle2[2];

              std::cout << "after: " << eulerAngle2[2] << ", " << std::endl;

              if (!useImuHeadingInitialization)
                transformTobeMapped[2] = 0;

              lastImuTransformation = pcl::getTransformation(0,
                                                             0,
                                                             0,
                                                             eulerAngle2[0],
                                                             eulerAngle2[1],
                                                             eulerAngle2[2]); // save imu before return;

              system_init = true;
              ROS_WARN("GPS init success");
            }
            else{
              ROS_ERROR("GPS NAN, waiting for a better yaw");
            }
            break;
          }
        }
      } else {
        transformTobeMapped[0] = cloudInfo.imuRollInit;
        transformTobeMapped[1] = cloudInfo.imuPitchInit;
        transformTobeMapped[2] = cloudInfo.imuYawInit;

        if (!useImuHeadingInitialization)
          transformTobeMapped[2] = 0;

        lastImuTransformation = pcl::getTransformation(0,
                                                       0,
                                                       0,
                                                       cloudInfo.imuRollInit,
                                                       cloudInfo.imuPitchInit,
                                                       cloudInfo.imuYawInit); // save imu before return;

        system_init = true;
      }

      return;
    }

    if (!system_init) {
      ROS_WARN("sysyem need to be inited");
      return;
    }

besides, i use the gps factor,

void addGPSFactor() {
    if (gpsQueue.empty())
      return;

    // wait for system initialized and settles down
    if (cloudKeyPoses3D->points.empty())
      return;
    else {
      if (pointDistance(cloudKeyPoses3D->front(), cloudKeyPoses3D->back()) < 5.0)
        return;
    }

    // pose covariance small, no need to correct
//    if (poseCovariance(3, 3) < poseCovThreshold && poseCovariance(4, 4) < poseCovThreshold)
//      return;

    // last gps position
    static PointType lastGPSPoint;

    while (!gpsQueue.empty()) {
      mutex_lock.lock();
      if (gpsQueue.front().header.stamp.toSec() < timeLaserInfoCur - 0.1) {
        // message too old
        gpsQueue.pop_front();
        mutex_lock.unlock();
      } else if (gpsQueue.front().header.stamp.toSec() > timeLaserInfoCur + 0.1) {
        // message too new
        mutex_lock.unlock();
        break;
      } else {
        nav_msgs::Odometry thisGPS = gpsQueue.front();
        gpsQueue.pop_front();
        mutex_lock.unlock();

        // GPS too noisy, skip
        float noise_x = thisGPS.pose.covariance[0];
        float noise_y = thisGPS.pose.covariance[7];
        float noise_z = thisGPS.pose.covariance[14];
        //if (noise_x > gpsCovThreshold || noise_y > gpsCovThreshold)
        if (noise_x > gpsCovThreshold || noise_y > gpsCovThreshold)
          continue;

        float gps_x = thisGPS.pose.pose.position.x;
        float gps_y = thisGPS.pose.pose.position.y;
        float gps_z = thisGPS.pose.pose.position.z;
        //if (!useGpsElevation) {
        //  gps_z = transformTobeMapped[5];
        //  noise_z = 0.01;
        // }

        //ROS_WARN(" gps lidar off time: %f ", off_time);
        std::cout << "currlidar pose: " << transformTobeMapped[3] << ", " << transformTobeMapped[4] << ", "
                  << transformTobeMapped[5] << std::endl;
        std::cout << "currGPS position: " << gps_x << ", "<< gps_y << ", "<< gps_z << std::endl;
        std::cout << "currGPS cov: " << thisGPS.pose.covariance[0] << ", " << thisGPS.pose.covariance[7]
                  << ", " << thisGPS.pose.covariance[14] << std::endl;

        // GPS not properly initialized (0,0,0)
        if (abs(gps_x) < 1e-6 && abs(gps_y) < 1e-6)
          continue;

        // Add GPS every a few meters
        PointType curGPSPoint;
        curGPSPoint.x = gps_x;
        curGPSPoint.y = gps_y;
        curGPSPoint.z = gps_z;
        if (pointDistance(curGPSPoint, lastGPSPoint) < 5.0)
          continue;
        else
          lastGPSPoint = curGPSPoint;

        gtsam::Vector Vector3(3);
        Vector3 << max(noise_x, 1.0f), max(noise_y, 1.0f), max(noise_z, 1.0f);
        noiseModel::Diagonal::shared_ptr gps_noise = noiseModel::Diagonal::Variances(Vector3);
        gtsam::GPSFactor gps_factor(cloudKeyPoses3D->size(), gtsam::Point3(gps_x, gps_y, gps_z), gps_noise);
        gtSAMgraph.add(gps_factor);

         aLoopIsClosed = true;
        break;
      }
    }
  }

because the gps data in my dataset is not very nice and it is really a large scale scene with huge elevation changes, but actually we need gps position to constrain the lidar pose. Or we can not close the final big loop.

if i use other loop detection methods, such as ScanContext, the final big loop can be successfully detetced, but the same problem happened.

we can see that we use the initial yaw from gps to init the system, it do not perfomed well because of the bad gps data. but after many gps factor adding into the pose graph, the trajectory aligned very well. Green path(GPS)

system begin image image

when i did not use the initial yaw from the gps to init system, the lidar trajectory and gps trajectory can not align, because no good gps data was adding to the pose graph. image

JokerJohn commented 2 years ago

when encounting small loops, the map optimization node runs well and lidar poses are also well constarined by gps data. image image

dsb6063 commented 2 years ago

As you have pointed out, the GPS covariance should be reviewed against the smaller set that worked. As the GPS part of the code becomes robust, these problems can handled. What I have concluded is that for us, we need to start the system using magnetic direction, since the project rarely provides good GPS coverage and time delay for fixed position. Furthermore, I will correct the vertical on the trajectory with survey ground points.

  1. Review covariance z
  2. For online SLAM, tougher problem, would require prior knowledge of starting xy, and z. Maybe closure can be done with post processing and substitute and average z value. 3. Modifying the code to assist with the decision would be necessary to contrain the z.
  3. Also, filter the GPS and provide a moving average of fixed positions like ekf to achieve a closure. Then, post process as necessary to coverage to a better solution.

I am working on the items now. As for additional information, the author provided the email to the person that assisted the that portion of the code.

Keep posting on how it resolves on shorter drives. Maybe, fuse vertical checks with imagery for short correction correlation.

JokerJohn commented 2 years ago

As you have pointed out, the GPS covariance should be reviewed against the smaller set that worked. As the GPS part of the code becomes robust, these problems can handled. What I have concluded is that for us, we need to start the system using magnetic direction, since the project rarely provides good GPS coverage and time delay for fixed position. Furthermore, I will correct the vertical on the trajectory with survey ground points.

  1. Review covariance z
  2. For online SLAM, tougher problem, would require prior knowledge of starting xy, and z. Maybe closure can be done with post processing and substitute and average z value. 3. Modifying the code to assist with the decision would be necessary to contrain the z.
  3. Also, filter the GPS and provide a moving average of fixed positions like ekf to achieve a closure. Then, post process as necessary to coverage to a better solution.

I am working on the items now. As for additional information, the author provided the email to the person that assisted the that portion of the code.

Keep posting on how it resolves on shorter drives. Maybe, fuse vertical checks with imagery for short correction correlation.

Thanks for your reply! when we do not use gps, the origin version of LIO-SAM can not close loop well and the points map appears to be layered, but the gtsam runs well with the dataset i provided above. the origin version of LIO-SAM (no gps)

To solve this problem, i try to add some other loop detection methods to enhance the radius search methods, such as ScanContext, the final big loop can be successfully detetced, but gtsam crashed again at almost the same location as the previous problem caused by gps.

Could it be that the loop constraint is too strong, causing the entire factor graph to collapse?Maybe it's the problem caused by gtsam?

dsb6063 commented 2 years ago

gtsam::IndeterminantLinearSystemException

If you expanded the radius for loop closure, then your covariance settings in LIO-SAM are excluding the elevations; therefore, the indeterminate system error. That is my guess. Try to change the z covariance to an unrealistic number, then decrease until the best result is obtained. The up and down jitter definitely can be the gps value held over the computed or estimated z. If you are having system resource latency, then downsample the cloud in LIO SAM and change the ICP value. All these items can be done with the bag file. Keep changing the params until the result is satisfactory.

Also, try enough test runs with the live system over clear skies and short runs to confirm the settings. Maybe slow speed on a few runs will help confirm the system resources and gps epochs to give a better result. Tall buildings (city) will experience multipath confusing most gps systems.

dsb6063 commented 2 years ago

Did you get your problem solved? I have a short drive that is uploaded with GPS without RTK corrections at this point. #312

stale[bot] commented 2 years ago

This issue has been automatically marked as stale because it has not had recent activity. It will be closed if no further activity occurs. Thank you for your contributions.

JokerJohn commented 2 years ago

Did you get your problem solved? I have a short drive that is uploaded with GPS without RTK corrections at this point. #312

I did not solve the problem of GPS fusion on this data, but I re-collected the data of the same scene, and made sure that the GPS data in the scene was relatively reliable, and there were some small closed loops in the scene, and finally got a new map successfully.

JokerJohn commented 2 years ago

This is my experiment result, ouster128+6axis-stim300 imu+normal GPS

dbea6a2cbca3f268431faac775e57b3
JokerJohn commented 2 years ago

I evaluated the performance and accuracy of various LIO algorithms on this scene, including fastlio2, lio-mapping, and fasterlio, and the datasets include handheld devices and car collections. It is found that LIO SAM is very stable when the overall data scene is highly balanced, but when the downhill speed is fast, there is a great probability of failure directly, which should be caused by the pre-integration node, causing the entire system to hang up. A very impressive scene is that when our car collects data, we need to go down the next step to the road. This step will lead to a large change in height and eventually cause the system to hang.

JokerJohn commented 2 years ago

gtsam::IndeterminantLinearSystemException

If you expanded the radius for loop closure, then your covariance settings in LIO-SAM are excluding the elevations; therefore, the indeterminate system error. That is my guess. Try to change the z covariance to an unrealistic number, then decrease until the best result is obtained. The up and down jitter definitely can be the gps value held over the computed or estimated z. If you are having system resource latency, then downsample the cloud in LIO SAM and change the ICP value. All these items can be done with the bag file. Keep changing the params until the result is satisfactory.

Also, try enough test runs with the live system over clear skies and short runs to confirm the settings. Maybe slow speed on a few runs will help confirm the system resources and gps epochs to give a better result. Tall buildings (city) will experience multipath confusing most gps systems.

I checked the error output log of the terminal again, and found that the pre-integration node should be the first to die when the system crashes, without any specific error type prompt. After that, the pre-integration node has been restarted, causing the back-end optimization node to raise gtsam::IndeterminantLinearSystemException

stale[bot] commented 2 years ago

This issue has been automatically marked as stale because it has not had recent activity. It will be closed if no further activity occurs. Thank you for your contributions.

cacao1987 commented 2 years ago

gtsam::IndeterminantLinearSystemException If you expanded the radius for loop closure, then your covariance settings in LIO-SAM are excluding the elevations; therefore, the indeterminate system error. That is my guess. Try to change the z covariance to an unrealistic number, then decrease until the best result is obtained. The up and down jitter definitely can be the gps value held over the computed or estimated z. If you are having system resource latency, then downsample the cloud in LIO SAM and change the ICP value. All these items can be done with the bag file. Keep changing the params until the result is satisfactory. Also, try enough test runs with the live system over clear skies and short runs to confirm the settings. Maybe slow speed on a few runs will help confirm the system resources and gps epochs to give a better result. Tall buildings (city) will experience multipath confusing most gps systems.

I checked the error output log of the terminal again, and found that the pre-integration node should be the first to die when the system crashes, without any specific error type prompt. After that, the pre-integration node has been restarted, causing the back-end optimization node to raise gtsam::IndeterminantLinearSystemException

have you solved this problem already?I also met this problem,could u tell me how to deal with. thanks for your kindness.

JokerJohn commented 2 years ago

gtsam::IndeterminantLinearSystemException If you expanded the radius for loop closure, then your covariance settings in LIO-SAM are excluding the elevations; therefore, the indeterminate system error. That is my guess. Try to change the z covariance to an unrealistic number, then decrease until the best result is obtained. The up and down jitter definitely can be the gps value held over the computed or estimated z. If you are having system resource latency, then downsample the cloud in LIO SAM and change the ICP value. All these items can be done with the bag file. Keep changing the params until the result is satisfactory. Also, try enough test runs with the live system over clear skies and short runs to confirm the settings. Maybe slow speed on a few runs will help confirm the system resources and gps epochs to give a better result. Tall buildings (city) will experience multipath confusing most gps systems.

I checked the error output log of the terminal again, and found that the pre-integration node should be the first to die when the system crashes, without any specific error type prompt. After that, the pre-integration node has been restarted, causing the back-end optimization node to raise gtsam::IndeterminantLinearSystemException

have you solved this problem already?I also met this problem,could u tell me how to deal with. thanks for your kindness.

I have solved this problem, I found that the covariance setting of GPS Factor requires some experience tuning, such as its weight level with odom factor.

cacao1987 commented 2 years ago

gtsam::IndeterminantLinearSystemException If you expanded the radius for loop closure, then your covariance settings in LIO-SAM are excluding the elevations; therefore, the indeterminate system error. That is my guess. Try to change the z covariance to an unrealistic number, then decrease until the best result is obtained. The up and down jitter definitely can be the gps value held over the computed or estimated z. If you are having system resource latency, then downsample the cloud in LIO SAM and change the ICP value. All these items can be done with the bag file. Keep changing the params until the result is satisfactory. Also, try enough test runs with the live system over clear skies and short runs to confirm the settings. Maybe slow speed on a few runs will help confirm the system resources and gps epochs to give a better result. Tall buildings (city) will experience multipath confusing most gps systems.

I checked the error output log of the terminal again, and found that the pre-integration node should be the first to die when the system crashes, without any specific error type prompt. After that, the pre-integration node has been restarted, causing the back-end optimization node to raise gtsam::IndeterminantLinearSystemException

have you solved this problem already?I also met this problem,could u tell me how to deal with. thanks for your kindness.

I have solved this problem, I found that the covariance setting of GPS Factor requires some experience tuning, such as its weight level with odom factor.

Thank you very much for your reply. I know the cause of the problem. Can you describe the optimization steps of GPS Factor in detail

emredmrcx commented 1 year ago

gtsam::IndeterminantLinearSystemException If you expanded the radius for loop closure, then your covariance settings in LIO-SAM are excluding the elevations; therefore, the indeterminate system error. That is my guess. Try to change the z covariance to an unrealistic number, then decrease until the best result is obtained. The up and down jitter definitely can be the gps value held over the computed or estimated z. If you are having system resource latency, then downsample the cloud in LIO SAM and change the ICP value. All these items can be done with the bag file. Keep changing the params until the result is satisfactory. Also, try enough test runs with the live system over clear skies and short runs to confirm the settings. Maybe slow speed on a few runs will help confirm the system resources and gps epochs to give a better result. Tall buildings (city) will experience multipath confusing most gps systems.

I checked the error output log of the terminal again, and found that the pre-integration node should be the first to die when the system crashes, without any specific error type prompt. After that, the pre-integration node has been restarted, causing the back-end optimization node to raise gtsam::IndeterminantLinearSystemException

have you solved this problem already?I also met this problem,could u tell me how to deal with. thanks for your kindness.

I have solved this problem, I found that the covariance setting of GPS Factor requires some experience tuning, such as its weight level with odom factor.

Hi. I am having same issues with my GPS, can you tell more about what you did to solve it?