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

Fix bug in LinearContainerFactor and warnings about Point3 #785

Merged
merged 2 commits into from
Jun 8, 2021
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion gtsam/nonlinear/LinearContainerFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -175,9 +175,10 @@ NonlinearFactor::shared_ptr LinearContainerFactor::rekey(
Values newLinearizationPoint;
for (size_t i = 0; i < factor_->size(); ++i) {
auto mapping = rekey_mapping.find(factor_->keys()[i]);
if (mapping != rekey_mapping.end())
if (mapping != rekey_mapping.end()) {
new_factor->factor_->keys()[i] = mapping->second;
newLinearizationPoint.insert(mapping->second, linearizationPoint_->at(mapping->first));
}
}
new_factor->linearizationPoint_ = newLinearizationPoint;

Expand Down
6 changes: 3 additions & 3 deletions gtsam/nonlinear/tests/testLinearContainerFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -326,13 +326,13 @@ TEST(TestLinearContainerFactor, Rekey) {
// Make an example factor
auto nonlinear_factor =
boost::make_shared<gtsam::BetweenFactor<gtsam::Point3>>(
gtsam::Symbol('x', 0), gtsam::Symbol('l', 0), gtsam::Point3(),
gtsam::Symbol('x', 0), gtsam::Symbol('l', 0), gtsam::Point3(0, 0, 0),
gtsam::noiseModel::Isotropic::Sigma(3, 1));

// Linearize and create an LCF
gtsam::Values linearization_pt;
linearization_pt.insert(gtsam::Symbol('x', 0), gtsam::Point3());
linearization_pt.insert(gtsam::Symbol('l', 0), gtsam::Point3());
linearization_pt.insert(gtsam::Symbol('x', 0), gtsam::Point3(0, 0, 0));
linearization_pt.insert(gtsam::Symbol('l', 0), gtsam::Point3(0, 0, 0));

LinearContainerFactor lcf_factor(
nonlinear_factor->linearize(linearization_pt), linearization_pt);
Expand Down