- edited description
High memory consumption with ISAM2.
Hello developers,
Thanks a lot for creating this amazing library. This is more of a question than an issue. I am working on Monocular Visual Odometry using ISAM2, and my pipeline simply involves the addition of genericProjectionFactors to images from landmarks, with projections equal to pixel coordinates from openCV tracking.
In the isam.update(graph, initial_values) step, my graph generally contains ~500 entities, mostly generic projection factors, along with a few (~5) Point3 landmarks, a between factor and a Pose3 pose. I run this update at an addition of every single image.
The issue I am facing is that the memory consumption of the program always remains very high and I end up consuming almost all of my system memory (16GB) by ~300 updates. Is this regular behaviour or is there a definite memory leak in my program? If the former, could you suggest what changes I may make to my pipeline to avoid this?
#include <Optimizer.h>
Optimizer::Optimizer() {
getOptimizerParams("params/optimizer_params.yaml", params_);
params_acquired_ = true;
}
Optimizer::~Optimizer() {
}
void Optimizer::getOptimizerParams(const string& optimizer_param_yaml,
Optimizer::optimizer_params& optimize_params) {
YAML::Node config = YAML::LoadFile(optimizer_param_yaml);
optimize_params.isam_relinearize_threshold = config["isam_relinearize_threshold"].as<float>();
optimize_params.isam_relinearize_skip = config["isam_relinearize_skip"].as<float>();
optimize_params.focal_length = config["focal_length"].as<float>();
optimize_params.cx = config["cx"].as<float>();
optimize_params.cy = config["cy"].as<float>();
optimize_params.image_height = config["image_height"].as<int>();
optimize_params.image_width = config["image_width"].as<int>();
}
bool Optimizer::optimizeGraph(Values& result) {
cout << "In Optimizer" << endl;
cout << "Size of cumulative_initial_values_: " << cumulative_initial_values_.keys().size() << endl;
isam.update(graph_, initial_values_);
cumulative_initial_values_ = isam.calculateEstimate();
result = cumulative_initial_values_;
//cumulative_initial_values_.print();
FastVector<long unsigned int> list_of_keys = cumulative_initial_values_.keys();
for(int m = 0 ; m < list_of_keys.size() ; m++ ) {
long unsigned int a = list_of_keys[m];
if(cumulative_initial_values_.at(a).dim() == 6) {
Pose3 temp = cumulative_initial_values_.at<Pose3>(a);
cout << "["<<temp.x()<<", " << temp.y() << ", " << temp.z() <<"]" << endl;
}
}
graph_.resize(0);
initial_values_ = Values();
first_update_done_ = true;
return true;
}
void Optimizer::addFeatureTrail(const FeatureTrailManager::SmartFeatureTrailPtr& trail) {
if(cumulative_initial_values_.exists(Symbol('l', trail->trail_id)) && first_update_done_ == true) { //purana
for (int i = 0; i < trail->features.size(); i++) {
gtsam::Point2 temp_pt(trail->features[i].keypoint.pt.x, trail->features[i].keypoint.pt.y);
if(initial_values_.exists(Symbol('x', trail->features[i].image_id))) {
if(temp_pt.x() > 0 && temp_pt.y() > 0 && temp_pt.x() < params_.image_width && temp_pt.y() < params_.image_height) {
Cal3_S2::shared_ptr K(new Cal3_S2(params_.focal_length, params_.focal_length, 0.0, params_.cx, params_.cy));
noiseModel::Isotropic::shared_ptr noise = noiseModel::Isotropic::Sigma(2, 0.5);
graph_.push_back(GenericProjectionFactor<Pose3, Point3, Cal3_S2>(temp_pt,
noise,
Symbol('x', trail->features[i].image_id),
Symbol('l', trail->trail_id),
K));
}
}
}
} else if (cumulative_initial_values_.exists(Symbol('l', trail->trail_id)) && first_update_done_ == false){
gtsam::Point2 temp_pt(trail->features.back().keypoint.pt.x, trail->features.back().keypoint.pt.y);
if(initial_values_.exists(Symbol('x', trail->features.back().image_id))) {
//cout << temp_pt << endl;
if(temp_pt.x() > 0 && temp_pt.y() > 0 && temp_pt.x() < params_.image_width && temp_pt.y() < params_.image_height) {
Cal3_S2::shared_ptr K(new Cal3_S2(params_.focal_length, params_.focal_length, 0.0, params_.cx, params_.cy));
noiseModel::Isotropic::shared_ptr noise = noiseModel::Isotropic::Sigma(2, 0.5);
graph_.push_back(GenericProjectionFactor<Pose3, Point3, Cal3_S2>(temp_pt,
noise,
Symbol('x', trail->features.back().image_id),
Symbol('l', trail->trail_id),
K));
}
}
} else if(!(cumulative_initial_values_.exists(Symbol('l', trail->trail_id)))) { //naya
vector<Pose3> poses_l;
vector<Point2> measurements_l;
for (int i = 0; i < trail->features.size(); i++) {
gtsam::Point2 temp_pt(trail->features[i].keypoint.pt.x, trail->features[i].keypoint.pt.y);
if(cumulative_initial_values_.exists(Symbol('x', trail->features[i].image_id))) {
if(temp_pt.x() > 0 && temp_pt.y() > 0 && temp_pt.x() < params_.image_width && temp_pt.y() < params_.image_height) {
poses_l.push_back(cumulative_initial_values_.at<Pose3>(Symbol('x', trail->features[i].image_id)));
measurements_l.push_back(temp_pt);
}
}
}
try {
Cal3_S2::shared_ptr K(new Cal3_S2(params_.focal_length, params_.focal_length, 0.0, params_.cx, params_.cy));
Point3 triangulated_pt = triangulatePoint3 (poses_l, K, measurements_l);
cumulative_initial_values_.insert(Symbol('l', trail->trail_id), triangulated_pt);
initial_values_.insert(Symbol('l', trail->trail_id), triangulated_pt);
for (int i = 0; i < trail->features.size(); i++) {
gtsam::Point2 temp_pt(trail->features[i].keypoint.pt.x, trail->features[i].keypoint.pt.y);
if(cumulative_initial_values_.exists(Symbol('x', trail->features[i].image_id))) {
if(temp_pt.x() > 0 && temp_pt.y() > 0 && temp_pt.x() < params_.image_width && temp_pt.y() < params_.image_height) {
noiseModel::Isotropic::shared_ptr noise = noiseModel::Isotropic::Sigma(2, 0.5);
graph_.push_back(GenericProjectionFactor<Pose3, Point3, Cal3_S2>(temp_pt,
noise,
Symbol('x', trail->features[i].image_id),
Symbol('l', trail->trail_id),
K));
}
}
}
} catch(gtsam::TriangulationCheiralityException& e) {
cout << e.what() << endl;
}
}
}
void Optimizer::addImage(const unsigned long image_id) {
noiseModel::Diagonal::shared_ptr large_noise = noiseModel::Diagonal::Sigmas(
(Vector(6) << Vector3::Constant(0.3), Vector3::Constant(1)).finished());
if(!cumulative_initial_values_.exists(Symbol('x',image_id))) {
Pose3 prev_prev_pose = cumulative_initial_values_.at<Pose3>(Symbol('x', image_id - 2));
Pose3 prev_pose = cumulative_initial_values_.at<Pose3>(Symbol('x', image_id - 1));
Point3 delta = (prev_pose.translation() - prev_prev_pose.translation()) * 0.9;
Point3 translation_after_delta = prev_pose.translation() + delta;
Rot3 delta_rot = cumulative_initial_values_.at<Pose3>(Symbol('x', image_id - 2)).rotation().inverse() * cumulative_initial_values_.at<Pose3>(Symbol('x', image_id - 1)).rotation();
cumulative_initial_values_.insert(Symbol('x', image_id), Pose3(cumulative_initial_values_.at<Pose3>(Symbol('x', image_id - 2)).rotation(),
translation_after_delta));
initial_values_.insert(Symbol('x', image_id), Pose3(cumulative_initial_values_.at<Pose3>(Symbol('x', image_id - 2)).rotation(),
translation_after_delta));
graph_.add(BetweenFactor<Pose3> (Symbol('x', image_id - 1),
Symbol('x', image_id),
Pose3(delta_rot,
delta),
large_noise));
}
}
void Optimizer::initGraph(gtsam::NonlinearFactorGraph prev_graph,
gtsam::Values prev_values) {
graph_ = prev_graph.clone();
initial_values_ = prev_values;
cumulative_initial_values_ = prev_values;
graph_.print("New Graph: ");
}
I am using GTSAM 4.0.0 on Ubuntu 16.04.2. Thanks a lot
Comments (6)
-
reporter -
reporter - edited description
-
Account Deactivated Did you checked valgrind tool? http://valgrind.org/gallery/linux_mag.html
gtsam use a lot dynamic memory allocation, this is typically expensive, but shouldn't be memory consumption(since all the dynamic memory allocation are well managed)
-
Thanks @IgnacioVizzo ! Valgrind seems like a good idea. If memory increases with iterations it could point to a leak. If in gt sam, please help us locate it ! Thanks !
-
-
assigned issue to
-
assigned issue to
-
- changed status to wontfix
No evidence that there is a leak. Will re-open if reporter investigates more with valgrind.
- Log in to comment