Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

segmentation fault if too many variables and constraints. #820

Closed
Tahiti410 opened this issue Jul 11, 2021 · 9 comments
Closed

segmentation fault if too many variables and constraints. #820

Tahiti410 opened this issue Jul 11, 2021 · 9 comments
Assignees
Labels
enhancement Improvement to GTSAM

Comments

@Tahiti410
Copy link

Tahiti410 commented Jul 11, 2021

Description

Segmentation fault if too many(about 140k) constraints and states.

I guess it's related to the resources release(recursive) in descrutors.

Steps to reproduce

  1. check/set the stack size of your machine by ulimit -s 8192
  2. Replace the code in example/LocalizationExample.cpp by code in Additional information.
  3. cd build
  4. build an run the demo program by make -j8 LocalizationExample && ./example/LocalizationExample

Expected behavior

Segmentation fault (core dumped)

Environment

Masterdevelop branch of gtsam
Linux version 5.4.0-52-generic (buildd@xxx-amd64-022) (gcc version 7.5.0 (Ubuntu 7.5.0-3ubuntu1~18.04)) #57~18.04.1-Ubuntu SMP Thu Oct 15 14:04:49 UTC 2020

ulimit -s output 8192

Additional information

#include <gtsam/geometry/Pose2.h>
#include <gtsam/inference/Key.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/Values.h>
#include <gtsam/slam/BetweenFactor.h>

using namespace std;
using namespace gtsam;

class UnaryFactor : public NoiseModelFactor1<Pose2> {
  double mx_, my_;

 public:
  typedef boost::shared_ptr<UnaryFactor> shared_ptr;
  UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model)
      : NoiseModelFactor1<Pose2>(model, j), mx_(x), my_(y) {}

  ~UnaryFactor() override {}
  Vector evaluateError(const Pose2& q, boost::optional<Matrix&> H = boost::none) const override {
    const Rot2& R = q.rotation();
    if (H) (*H) = (gtsam::Matrix(2, 3) << R.c(), -R.s(), 0.0, R.s(), R.c(), 0.0).finished();
    return (Vector(2) << q.x() - mx_, q.y() - my_).finished();
  }
  gtsam::NonlinearFactor::shared_ptr clone() const override {
    return boost::static_pointer_cast<gtsam::NonlinearFactor>(
        gtsam::NonlinearFactor::shared_ptr(new UnaryFactor(*this)));
  }
};

int main(int argc, char** argv) {
  NonlinearFactorGraph graph;
  const auto odom_noise = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
  const auto unary_noise = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1));
  Values initial_state;

  const int num_state = 135250;
  graph.emplace_shared<UnaryFactor>(0, 0.0, 0.0, unary_noise);
  graph.emplace_shared<UnaryFactor>(num_state - 1, num_state * 1.0, 0.0, unary_noise);
  for (int i = 0; i < num_state; ++i) {
    initial_state.insert(i, Pose2(i, 0.0, 0.0));
  }
  for (int i = 0; i < num_state - 1; ++i) {
    graph.emplace_shared<BetweenFactor<Pose2> >(i, i + 1, Pose2(1.0, 0.0, 0.0), odom_noise);
  }

  LevenbergMarquardtOptimizer optimizer(graph, initial_state);
  std::cout << "Start to optimize." << std::endl;
  const Values result = optimizer.optimize();
  std::cout << "Optimization finished." << std::endl;
  if (result.exists(num_state - 1)) {
    const Pose2 end_pose = result.at<Pose2>(num_state - 1);
    end_pose.print("End pose2:\n");
  }

  return 0;
}
@Tahiti410
Copy link
Author

cc @ProfFan thanks~

@ProfFan ProfFan added the bug Bug report label Jul 11, 2021
@ProfFan
Copy link
Collaborator

ProfFan commented Jul 11, 2021

Hi @Tahiti410 , by "Master code of gtsam" do you mean master or develop? develop is the latest branch.

@Tahiti410
Copy link
Author

Hi @Tahiti410 , by "Master code of gtsam" do you mean master or develop? develop is the latest branch.

Sorry, it's develop branch

@ProfFan
Copy link
Collaborator

ProfFan commented Jul 12, 2021

I think this is also related to #809. A race condition caused the stack to overflow. @acxz @varunagrawal We should probably revert #800 for now to unbreak develop and find the ultimate cause.

@ProfFan
Copy link
Collaborator

ProfFan commented Jul 12, 2021

In the meantime, @Tahiti410 could you try the fix mentioned in #809 ?

@ProfFan
Copy link
Collaborator

ProfFan commented Jul 12, 2021

Though this can be an issue of the multifrontal solver in the presence of large chains like the one in this reproducer. I am not sure.

EDIT: This IS the cause.

@ProfFan
Copy link
Collaborator

ProfFan commented Jul 12, 2021

Maybe this:

      void processNodeRecursively(const boost::shared_ptr<NODE>& node, DATA& myData)
        {
          for(const boost::shared_ptr<NODE>& child: node->children)
          {
            DATA childData = visitorPre(child, myData);
            processNodeRecursively(child, childData);
          }

          // Run the post-order visitor
          (void) visitorPost(node, myData);
        }
      };

should be rewritten to not use recursion.

@ProfFan
Copy link
Collaborator

ProfFan commented Jul 12, 2021

Ok, by using ulimit -s 65535 I don't get crashes anymore. So this is not a TBB issue. @Tahiti410

But still it would be great if we can do this without needing to change ulimit.

@ProfFan ProfFan added enhancement Improvement to GTSAM and removed bug Bug report labels Jul 15, 2021
@ProfFan
Copy link
Collaborator

ProfFan commented Nov 9, 2021

Closing as this is resolved.

@ProfFan ProfFan closed this as completed Nov 9, 2021
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
enhancement Improvement to GTSAM
Projects
None yet
Development

No branches or pull requests

3 participants