cartographer: Residual Block Error
Started using the cartographer_turtlebot package in simulation, and I’ve been running into this error. It occurs after a random amount of time ranging from a few seconds after starting the cartographer_node to several minutes- the only changes I’ve made have been remapping a few topic names (mainly odometry and the laser scanner), removing a line launching turtlebot’s minimal bringup and a line launching the urg_node (since I’m using my own version of turtlebot) and disabling the imu (changes have been across this file and this file). The file I’ve been launching from is here. The error I’ve been getting is shown below:
[ WARN] [1491490574.176173648, 624.161000000]: W0406 10:56:14.000000 8798 residual_block.cc:131]
Error in evaluating the ResidualBlock.
There are two possible reasons. Either the CostFunction did not evaluate and fill all
residual and jacobians that were requested or there was a non-finite value (nan/infinite)
generated during the or jacobian computation.
Residual Block size: 1 parameter blocks x 184 residuals
For each parameter block, the value of the parameters are printed in the first column
and the value of the jacobian under the corresponding residual. If a ParameterBlock was
held constant then the corresponding jacobian is printed as 'Not Computed'. If an entry
of the Jacobian/residual array was requested but was not written to by user code, it is
indicated by 'Uninitialized'. This is an error. Residuals or Jacobian values evaluating
to Inf or NaN is also an error.
Residuals: nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan nan
Parameter Block 0, size: 3
nan | -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan
nan | -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan
-0.0744971 | -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan -nan
CHOLMOD error: invalid xtype
F0406 10:56:14.176298 8798 covariance_impl.cc:652] Check failed: 'permutation' Must be non NULL
[FATAL] [1491490574.176547018, 624.161000000]: F0406 10:56:14.000000 8798 covariance_impl.cc:652] Check failed: 'permutation' Must be non NULL
*** Check failure stack trace: ***
@ 0x7ffff7bb35cd google::LogMessage::Fail()
@ 0x7ffff7bb5433 google::LogMessage::SendToLog()
@ 0x7ffff7bb315b google::LogMessage::Flush()
@ 0x7ffff7bb5e1e google::LogMessageFatal::~LogMessageFatal()
@ 0x6546e1 ceres::internal::CovarianceImpl::ComputeCovarianceValuesUsingSuiteSparseQR()
@ 0x65b0a5 ceres::internal::CovarianceImpl::ComputeCovarianceValues()
@ 0x65b22f ceres::internal::CovarianceImpl::Compute()
@ 0x5a6918 cartographer::mapping_2d::scan_matching::CeresScanMatcher::Match()
@ 0x5ae390 cartographer::mapping_2d::LocalTrajectoryBuilder::ScanMatch()
@ 0x5ae94e cartographer::mapping_2d::LocalTrajectoryBuilder::AddHorizontalRangeData()
@ 0x5acfbc cartographer::mapping_2d::GlobalTrajectoryBuilder::AddRangefinderData()
@ 0x5377f9 cartographer::mapping::CollatedTrajectoryBuilder::HandleCollatedSensorData()
@ 0x53822e _ZNSt17_Function_handlerIFvRKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEESt10unique_ptrIN12cartographer6sensor4DataESt14default_deleteISB_EEEZNS9_7mapping25CollatedTrajectoryBuilderC4EPNSA_8CollatorEiRKSt13unordered_setIS5_St4hashIS5_ESt8equal_toIS5_ESaIS5_EES8_INSG_32GlobalTrajectoryBuilderInterfaceESC_IST_EEEUlS7_SE_E_E9_M_invokeERKSt9_Any_dataS7_OSE_
@ 0x61327a _ZNSt17_Function_handlerIFvSt10unique_ptrIN12cartograp9_Any_dataOS6_
@ 0x6171f9 cartographer::sensor::OrderedMultiQueue::Dispatch()
@ 0x61879f cartographer::sensor::OrderedMultiQueue::Add()
@ 0x613574 cartographer::sensor::Collator::AddSensorData()
@ 0x536948 cartographer::mapping::CollatedTrajectoryBuilder::AddS
@ 0x509f5b cartographer_ros::SensorBridge::HandleRangefinder()
@ 0x50ab9a cartographer_ros::SensorBridge::HandleLaserScanMessage
@ 0x4efb2b _ZN5boost6detail8function26void_function_obj_invoker1I
@ 0x4f6c4e boost::detail::function::void_function_obj_invoker1<>:
@ 0x500e39 ros::SubscriptionCallbackHelperT<>::call()
@ 0x7ffff4d1c5cd ros::SubscriptionQueue::call()
@ 0x7ffff4cc6cf0 ros::CallbackQueue::callOneCB()
@ 0x7ffff4cc80f3 ros::CallbackQueue::callAvailable()
@ 0x7ffff4d20691 ros::SingleThreadedSpinner::spin()
@ 0x7ffff4d0572b ros::spin()
@ 0x4f0f6e cartographer_ros::(anonymous namespace)::Run()
@ 0x4ed6a4 main
@ 0x7ffff371f830 __libc_start_main
@ 0x4ef129 _start
Thread 1 "cartographer_no" received signal SIGABRT, Aborted.
0x00007ffff3734428 in __GI_raise (sig=sig@entry=6)
at ../sysdeps/unix/sysv/linux/raise.c:54
54 ../sysdeps/unix/sysv/linux/raise.c: No such file or directory.
It’s also worth noting that this error occurs regardless of if the robot stands still or moves- and while moving, does correctly generate a map. I’ve tested running the 2D Lidar Demo (listed here) with imu disabled and no other changes, in order to make sure the disabled imu wasn’t causing the issue. It ran without error under those circumstances. I’m using Ubuntu 16.04 and ROS Kinetic.
About this issue
- Original URL
- State: closed
- Created 7 years ago
- Reactions: 1
- Comments: 19 (5 by maintainers)
Commits related to this issue
- Fix divison by zero. If mapping_2d::LocalTrajectoryBuilder::AddHorizontalRangeData is called twice in a row with the same `time`, the `velocity_estimate_` becomes `inf` which led to `inf`s in the opt... — committed to SirVer/cartographer by SirVer 7 years ago
- Fix divison by zero. (#240) If mapping_2d::LocalTrajectoryBuilder::AddHorizontalRangeData is called twice in a row with the same `time`, the `velocity_estimate_` becomes `inf` which led to `inf`s i... — committed to cartographer-project/cartographer by SirVer 7 years ago
- Fix the offline 3D backpack launch file. (#233) — committed to damienrg/cartographer by wohe 8 years ago
This is a bug in SuiteSparse v4.4.6. Modify the Ceres CMakeLists.txt file to use EigenSparse instead of SuiteSparse and recompile.