diff --git a/gtsam/nonlinear/Values.cpp b/gtsam/nonlinear/Values.cpp index a6804c1a6..bb66943eb 100644 --- a/gtsam/nonlinear/Values.cpp +++ b/gtsam/nonlinear/Values.cpp @@ -165,10 +165,8 @@ namespace gtsam { /* ************************************************************************* */ FastList Values::keys() const { FastList result; - for(const_iterator key_value = begin(); key_value != end(); ++key_value) { + for(const_iterator key_value = begin(); key_value != end(); ++key_value) result.push_back(key_value->key); - cout << result.back() << endl; - } return result; } diff --git a/matlab/VisualISAMPlot.m b/matlab/VisualISAMPlot.m index 90c542662..a2950b5dc 100644 --- a/matlab/VisualISAMPlot.m +++ b/matlab/VisualISAMPlot.m @@ -10,9 +10,9 @@ cla(h); hold on; %% Plot points -pointKeys = result.allPoints().keys(); -for j=0:N-1 % NOTE: uses indexing directly from a C++ vector, so zero-indexed - jj = pointKeys.at(j); +for k=1:length(data.J{M}) + j = data.J{M}{k}; + jj = symbol('l', j); point_j = result.point(jj); plot3(point_j.x, point_j.y, point_j.z,'marker','o'); P = isam.marginalCovariance(jj);