Skip to content

Commit

Permalink
make fix variable types customizable
Browse files Browse the repository at this point in the history
  • Loading branch information
koide3 committed Dec 12, 2024
1 parent 0f8e2f3 commit be9c4dc
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@ class IncrementalFixedLagSmootherExtWithFallback : public IncrementalFixedLagSmo
IncrementalFixedLagSmootherExtWithFallback(double smootherLag, const ISAM2Params& parameters);
~IncrementalFixedLagSmootherExtWithFallback() override;

void set_fix_variable_types(const std::vector<std::pair<char, int>>& var_types) { fix_variable_types = var_types; }

Result update(
const gtsam::NonlinearFactorGraph& newFactors = gtsam::NonlinearFactorGraph(),
const gtsam::Values& newTheta = gtsam::Values(), //
Expand Down Expand Up @@ -69,5 +71,7 @@ class IncrementalFixedLagSmootherExtWithFallback : public IncrementalFixedLagSmo
mutable gtsam::FixedLagSmootherKeyTimestampMap stamps;

mutable std::unique_ptr<IncrementalFixedLagSmootherExt> smoother;

std::vector<std::pair<char, int>> fix_variable_types; // (chr, type) type: 0=Pose3, 1=Point3
};
} // namespace gtsam_points
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,8 @@
namespace gtsam_points {

IncrementalFixedLagSmootherExtWithFallback::IncrementalFixedLagSmootherExtWithFallback(double smootherLag, const ISAM2Params& parameters)
: IncrementalFixedLagSmootherExt(smootherLag, parameters) {
: IncrementalFixedLagSmootherExt(smootherLag, parameters),
fix_variable_types({{'x', 0}}) {
fallback_happend = false;
current_stamp = 0.0;
smoother.reset(new IncrementalFixedLagSmootherExt(smootherLag, parameters));
Expand Down Expand Up @@ -273,11 +274,28 @@ void IncrementalFixedLagSmootherExtWithFallback::fallback_smoother() const {
const int dim = value.value.dim();
new_factors.emplace_shared<gtsam_points::LinearDampingFactor>(value.key, dim, 1e6);

if (symbol.chr() == 'x') {
new_factors.emplace_shared<gtsam::PriorFactor<gtsam::Pose3>>(
value.key,
gtsam::Pose3(value.value.cast<gtsam::Pose3>()),
gtsam::noiseModel::Isotropic::Precision(6, 1e6));
for (const auto var_type : fix_variable_types) {
if (symbol.chr() == var_type.first) {
std::cout << "fixing " << symbol << std::endl;
switch (var_type.second) {
case 0:
new_factors.emplace_shared<gtsam::PriorFactor<gtsam::Pose3>>(
value.key,
value.value.cast<gtsam::Pose3>(),
gtsam::noiseModel::Isotropic::Precision(6, 1e6));
break;
case 1:
new_factors.emplace_shared<gtsam::PriorFactor<gtsam::Vector3>>(
value.key,
value.value.cast<gtsam::Vector3>(),
gtsam::noiseModel::Isotropic::Precision(3, 1e6));
break;
default:
std::cerr << "error: unknown variable type!! (chr=" << static_cast<int>(var_type.first) << " type=" << var_type.second << ")"
<< std::endl;
break;
}
}
}
}

Expand Down

0 comments on commit be9c4dc

Please sign in to comment.