cartographer-project / cartographer

Cartographer is a system that provides real-time simultaneous localization and mapping (SLAM) in 2D and 3D across multiple platforms and sensor configurations.
Apache License 2.0
7.04k stars 2.24k forks source link

Setting gravity constant lower bound causes crash when finishing a trajectory #1841

Closed hlinhn closed 2 years ago

hlinhn commented 3 years ago

I am running a locally built version of cartographer (built at 105c034577220268cd28a304a185adbec46b729f) on Linux 5.4.0-73-generic

Upon finishing a newly created trajectory (after sending the first initial pose in localization only mode to cartographer_ros), cartographer sometimes crashes with the following trace:

F0519 10:35:41.948809 12819 problem_impl.cc:698] Parameter block not found: 0x7f90ec05aa20. You must add the parameter block to the problem before you can set a lower bound on one of its components.
[FATAL] [1621391741.949467829][/cartographer/cartographer_node][/var/jenkins_home/workspace/cartographer_ros_focal/ws/src/cartographer_ros/cartographer_ros/cartographer_ros/ros_log_sink.cc:63]: F0519 10:35:41.000000 12819 problem_impl.cc:698] Parameter block not found: 0x7f90ec05aa20. You must add the parameter block to the problem before you can set a lower bound on one of its components.
*** Check failure stack trace: ***
    @     0x7f91173411c3  google::LogMessage::Fail()
    @     0x7f911734625b  google::LogMessage::SendToLog()
    @     0x7f9117340ebf  google::LogMessage::Flush()
    @     0x7f91173416ef  google::LogMessageFatal::~LogMessageFatal()
    @     0x7f91174afddc  ceres::internal::ProblemImpl::SetParameterLowerBound()
    @     0x55ecda889667  cartographer::mapping::optimization::OptimizationProblem3D::Solve()
    @     0x55ecda841ce0  cartographer::mapping::PoseGraph3D::RunOptimization()
    @     0x55ecda8429b1  cartographer::mapping::PoseGraph3D::HandleWorkQueue()
    @     0x55ecda860de2  cartographer::mapping::constraints::ConstraintBuilder3D::RunWhenDoneCallback()
    @     0x55ecda8c6ca5  cartographer::common::Task::Execute()
    @     0x55ecda7f8951  cartographer::common::ThreadPool::DoWork()
    @     0x7f9116973d84  (unknown)
    @     0x7f9116e76609  start_thread
    @     0x7f9116661293  clone

I suspect that it was caused by having only one node in the first non-frozen trajectory (hence this parameter block https://github.com/cartographer-project/cartographer/blob/a54e72ec1ee47b4eb8a23581069abd44008668e9/cartographer/mapping/internal/optimization/optimization_problem_3d.cc#L422-L434 was not added), causing the crash at https://github.com/cartographer-project/cartographer/blob/a54e72ec1ee47b4eb8a23581069abd44008668e9/cartographer/mapping/internal/optimization/optimization_problem_3d.cc#L446

It is a little difficult to reproduce this issue reliably, but setting TRAJECTORY_BUILDER_3D.motion_filter.max_time_seconds to a high number and having the tracking frame not moving while sending the first initial pose in localization only mode seems to help with reproducing it.