Assertion failures in Debug mode

Issue #100 resolved
Chris Beall created an issue

@fdellaert , it looks like your changes to NoiseModel are the cause of some assertion failures in Debug mode. Are you still working on this?

For example, testNonlinearEquality:

#0  0x00007f7500d18037 in __GI_raise (sig=sig@entry=6) at ../nptl/sysdeps/unix/sysv/linux/raise.c:56
#1  0x00007f7500d1b698 in __GI_abort () at abort.c:90
#2  0x00007f7500d10e03 in __assert_fail_base (fmt=0x7f7500e68158 "%s%s%s:%u: %s%sAssertion `%s' failed.\n%n", 
    assertion=assertion@entry=0x4f0eee "index >= 0 && index < size()", 
    file=file@entry=0x4f0ea0 "/home/cbeall3/git/gtsam/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseCoeffsBase.h", line=line@entry=173, 
    function=function@entry=0x4f3940 <Eigen::DenseCoeffsBase<Eigen::Matrix<double, -1, 1, 0, -1, 1>, 0>::operator()(long) const::__PRETTY_FUNCTION__> "Eigen::DenseCoeffsBase<Derived, 0>::CoeffReturnType Eigen::DenseCoeffsBase<Derived, 0>::operator()(Eigen::DenseCoeffsBase<Derived, 0>::Index) const [with Derived = Eigen::Matrix<double, -1, 1>; Eigen:"...) at assert.c:92
#3  0x00007f7500d10eb2 in __GI___assert_fail (assertion=0x4f0eee "index >= 0 && index < size()", 
    file=0x4f0ea0 "/home/cbeall3/git/gtsam/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseCoeffsBase.h", line=173, 
    function=0x4f3940 <Eigen::DenseCoeffsBase<Eigen::Matrix<double, -1, 1, 0, -1, 1>, 0>::operator()(long) const::__PRETTY_FUNCTION__> "Eigen::DenseCoeffsBase<Derived, 0>::CoeffReturnType Eigen::DenseCoeffsBase<Derived, 0>::operator()(Eigen::DenseCoeffsBase<Derived, 0>::Index) const [with Derived = Eigen::Matrix<double, -1, 1>; Eigen:"...) at assert.c:101
#4  0x00000000004b80c2 in Eigen::DenseCoeffsBase<Eigen::Matrix<double, -1, 1, 0, -1, 1>, 0>::operator() (this=0x7fff5822e010, index=0)
    at /home/cbeall3/git/gtsam/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseCoeffsBase.h:173
#5  0x00007f7502661352 in gtsam::noiseModel::Diagonal::Sigmas (sigmas=..., smart=true) at /home/cbeall3/git/gtsam/gtsam/linear/NoiseModel.cpp:230
#6  0x00007f750269c488 in gtsam::JacobianFactor::splitConditional (this=0x10ef520, nrFrontals=2) at /home/cbeall3/git/gtsam/gtsam/linear/JacobianFactor.cpp:717
#7  0x00007f750269bcd8 in gtsam::EliminateQR (factors=..., keys=...) at /home/cbeall3/git/gtsam/gtsam/linear/JacobianFactor.cpp:667
#8  0x00007f75026371fd in gtsam::EliminatePreferCholesky (factors=..., keys=...) at /home/cbeall3/git/gtsam/gtsam/linear/HessianFactor.cpp:644
#9  0x00007f75026cf913 in boost::detail::function::function_invoker2<std::pair<boost::shared_ptr<gtsam::GaussianConditional>, boost::shared_ptr<gtsam::GaussianFactor> > (*)(gtsam::GaussianFactorGraph const&, gtsam::Ordering const&), std::pair<boost::shared_ptr<gtsam::GaussianConditional>, boost::shared_ptr<gtsam::GaussianFactor> >, gtsam::GaussianFactorGraph const&, gtsam::Ordering const&>::invoke (function_ptr=..., a0=..., a1=...) at /usr/include/boost/function/function_template.hpp:95
#10 0x00007f750262c4ff in boost::function2<std::pair<boost::shared_ptr<gtsam::GaussianConditional>, boost::shared_ptr<gtsam::GaussianFactor> >, gtsam::GaussianFactorGraph const&, gtsam::Ordering const&>::operator() (this=0x7fff5822eb50, a0=..., a1=...) at /usr/include/boost/function/function_template.hpp:760
#11 0x00007f750262365e in gtsam::(anonymous namespace)::EliminationPostOrderVisitor<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> >::operator() (this=0x7fff5822e6c0, node=..., myData=...) at /home/cbeall3/git/gtsam/gtsam/inference/ClusterTree-inst.h:102
#12 0x00007f7502622092 in gtsam::treeTraversal::DepthFirstForest<const gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph>, gtsam::{anonymous}::EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> >, gtsam::{anonymous}::EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> >(const boost::shared_ptr<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph>::Cluster>&, gtsam::{anonymous}::EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> >&), gtsam::{anonymous}::EliminationPostOrderVisitor<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> > >(const gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> &, gtsam::(anonymous namespace)::EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> > &, gtsam::(anonymous namespace)::EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> > (&)(const boost::shared_ptr<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph>::Cluster> &, gtsam::(anonymous namespace)::EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> > &), gtsam::(anonymous namespace)::EliminationPostOrderVisitor<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> > &) (forest=..., rootData=..., visitorPre=
    @0x7f7502620b9e: {gtsam::(anonymous namespace)::EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> > (const boost::shared_ptr<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph>::Cluster> &, gtsam::(anonymous namespace)::EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> > &)} 0x7f7502620b9e <gtsam::(anonymous namespace)::eliminationPreOrderVisitor<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> >(gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph>::sharedNode const&, gtsam::(anonymous namespace)::EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> >&)>, visitorPost=...) at /home/cbeall3/git/gtsam/gtsam/base/treeTraversal-inst.h:103
#13 0x00007f7502620c66 in gtsam::treeTraversal::DepthFirstForestParallel<const gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph>, gtsam::{anonymous}::EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> >, gtsam::{anonymous}::EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> >(const boost::shared_ptr<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph>::Cluster>&, gtsam::{anonymous}::EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> >&), gtsam::{anonymous}::EliminationPostOrderVisitor<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> > >(const gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> &, gtsam::(anonymous namespace):---Type <return> to continue, or q <return> to quit---
:EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> > &, gtsam::(anonymous namespace)::EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> > (&)(const boost::shared_ptr<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph>::Cluster> &, gtsam::(anonymous namespace)::EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> > &), gtsam::(anonymous namespace)::EliminationPostOrderVisitor<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> > &, int) (forest=..., rootData=..., visitorPre=
    @0x7f7502620b9e: {gtsam::(anonymous namespace)::EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> > (const boost::shared_ptr<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph>::Cluster> &, gtsam::(anonymous namespace)::EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> > &)} 0x7f7502620b9e <gtsam::(anonymous namespace)::eliminationPreOrderVisitor<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> >(gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph>::sharedNode const&, gtsam::(anonymous namespace)::EliminationData<gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph> >&)>, visitorPost=..., problemSizeThreshold=10)
    at /home/cbeall3/git/gtsam/gtsam/base/treeTraversal-inst.h:163
#14 0x00007f7502626afe in gtsam::ClusterTree<gtsam::GaussianBayesTree, gtsam::GaussianFactorGraph>::eliminate(boost::function<std::pair<boost::shared_ptr<gtsam::GaussianConditional>, boost::shared_ptr<gtsam::GaussianFactor> > (gtsam::GaussianFactorGraph const&, gtsam::Ordering const&)> const&) const (this=0x7fff5822e850, 
    function=...) at /home/cbeall3/git/gtsam/gtsam/inference/ClusterTree-inst.h:167
#15 0x00007f75026b4b22 in gtsam::EliminateableFactorGraph<gtsam::GaussianFactorGraph>::eliminateMultifrontal(boost::optional<gtsam::Ordering const&>, boost::function<std::pair<boost::shared_ptr<gtsam::GaussianConditional>, boost::shared_ptr<gtsam::GaussianFactor> > (gtsam::GaussianFactorGraph const&, gtsam::Ordering const&)> const&, boost::optional<gtsam::VariableIndex const&>) const (this=0x7fff5822ed40, ordering=..., function=..., variableIndex=...)
    at /home/cbeall3/git/gtsam/gtsam/inference/EliminateableFactorGraph-inst.h:73
#16 0x00007f75026b4cc6 in gtsam::EliminateableFactorGraph<gtsam::GaussianFactorGraph>::eliminateMultifrontal(boost::optional<gtsam::Ordering const&>, boost::function<std::pair<boost::shared_ptr<gtsam::GaussianConditional>, boost::shared_ptr<gtsam::GaussianFactor> > (gtsam::GaussianFactorGraph const&, gtsam::Ordering const&)> const&, boost::optional<gtsam::VariableIndex const&>) const (this=0x7fff5822ed40, ordering=..., function=..., variableIndex=...)
    at /home/cbeall3/git/gtsam/gtsam/inference/EliminateableFactorGraph-inst.h:84
#17 0x00007f75026b0de9 in gtsam::GaussianFactorGraph::optimize(boost::optional<gtsam::Ordering const&>, boost::function<std::pair<boost::shared_ptr<gtsam::GaussianConditional>, boost::shared_ptr<gtsam::GaussianFactor> > (gtsam::GaussianFactorGraph const&, gtsam::Ordering const&)> const&) const (this=0x7fff5822ed40, ordering=..., 
    function=...) at /home/cbeall3/git/gtsam/gtsam/linear/GaussianFactorGraph.cpp:254
#18 0x00007f7502753335 in gtsam::NonlinearOptimizer::solve (this=0x7fff5822f4b0, gfg=..., initial=..., params=...)
    at /home/cbeall3/git/gtsam/gtsam/nonlinear/NonlinearOptimizer.cpp:101
#19 0x00007f75026f3a5d in gtsam::LevenbergMarquardtOptimizer::iterate (this=0x7fff5822f4b0)
    at /home/cbeall3/git/gtsam/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp:241
#20 0x00007f7502752f75 in gtsam::NonlinearOptimizer::defaultOptimize (this=0x7fff5822f4b0) at /home/cbeall3/git/gtsam/gtsam/nonlinear/NonlinearOptimizer.cpp:69
#21 0x00000000004b3ffe in gtsam::NonlinearOptimizer::optimize (this=0x7fff5822f4b0) at /home/cbeall3/git/gtsam/gtsam/nonlinear/NonlinearOptimizer.h:155
#22 0x00000000004ab36d in testNonlinearEqualityConstraintmap_warpTest::run (this=0x72b820 <testNonlinearEqualityConstraintmap_warpInstance>, result_=...)
    at /home/cbeall3/git/gtsam/tests/testNonlinearEquality.cpp:497
#23 0x00000000004eef5a in TestRegistry::run (this=0x72c0f0 <TestRegistry::instance()::registry>, result=...)
    at /home/cbeall3/git/gtsam/CppUnitLite/TestRegistry.cpp:62
#24 0x00000000004eee56 in TestRegistry::runAllTests (result=...) at /home/cbeall3/git/gtsam/CppUnitLite/TestRegistry.cpp:29
#25 0x00000000004acc6d in main () at /home/cbeall3/git/gtsam/tests/testNonlinearEquality.cpp:577

Comments (6)

  1. Frank Dellaert

    I don't get it! Here is the code in NoiseModel.cpp:

    Diagonal::shared_ptr Diagonal::Sigmas(const Vector& sigmas, bool smart) {
      if (smart) {
        size_t n = sigmas.size();
        // look for zeros to make a constraint
        for (size_t j=0; j< n; ++j)
          if (sigmas(j)<1e-8)
            return Constrained::MixedSigmas(sigmas);
        // check whether all the same entry
        for (size_t j = 1; j < n; j++)
          if (sigmas(j) != sigmas(0)) goto full;
        return Isotropic::Sigma(n, sigmas(0), true);
      }
      full: return Diagonal::shared_ptr(new Diagonal(sigmas));
    }
    

    It fails here, but I can't see why:

    if (sigmas(j) != sigmas(0))
    
  2. Chris Beall reporter

    I think it's actually the line after that. n=0, which probably should never happen.

    (lldb) frame variable
    (const Vector &) sigmas = 0x00007fff5fbfc8f0: {
      Eigen::PlainObjectBase<Eigen::Matrix<double, 4294967295, 1, 0, 4294967295, 1> > = {
        m_storage = {
          m_data = 0x0000000103207510
          m_rows = 0
        }
      }
    }
    (bool) smart = true
    (gtsam::DenseIndex) j = 1
    (gtsam::DenseIndex) n = 0
    
  3. Log in to comment