35 using namespace gtsam;
49 for (
const auto &edge : relativeTranslations) {
52 if (key1 != key2 && edge.measured().equals(
Unit3(0.0, 0.0, 0.0))) {
53 sameTranslationDSF.
merge(key1, key2);
57 for (
const auto &edge : relativeTranslations) {
60 if (key1 == key2)
continue;
74 edge.measured(), edge.noiseModel());
88 edge->key2(), scale * edge->measured().point3(), edge->noiseModel());
111 Key optimizedKey = optimizedAndDuplicateKeys.first;
129 Key optimizedKey = optimizedAndDuplicateKeys.first;
130 std::set<Key> duplicateKeys = optimizedAndDuplicateKeys.second;
132 for (
const Key duplicateKey : duplicateKeys) {
133 if (result.
exists(duplicateKey))
continue;
141 const Values &poses,
const vector<KeyPair> &
edges) {
144 for (
auto edge : edges) {
149 const Unit3 w_aZb(Tb - Ta);
150 relativeTranslations.emplace_back(a, b, w_aZb, edgeNoiseModel);
152 return relativeTranslations;
vector< MFAS::KeyPair > edges
virtual const Values & optimize()
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
void merge(const KEY &x, const KEY &y)
Merge two sets.
void insert(Key j, const Value &val)
KEY find(const KEY &key) const
Given key, find the representative key for the set in which it lives.
void addPrior(const double scale, NonlinearFactorGraph *graph, const SharedNoiseModel &priorNoiseModel=noiseModel::Isotropic::Sigma(3, 0.01)) const
Add priors on ednpoints of first measurement edge.
std::map< Key, std::set< Key > > sameTranslationNodes_
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
NonlinearFactorGraph graph
Values run(const double scale=1.0) const
Build and optimize factor graph.
const Symbol key1('v', 1)
static TranslationEdges SimulateMeasurements(const Values &poses, const std::vector< KeyPair > &edges)
Simulate translation direction measurements.
Represents a 3D point on a unit sphere.
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
const ValueType at(Key j) const
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Binary factor for a relative translation direction measurement.
TranslationRecovery(const TranslationEdges &relativeTranslations, const LevenbergMarquardtParams &lmParams=LevenbergMarquardtParams())
Construct a new Translation Recovery object.
NonlinearFactorGraph buildGraph() const
Build the factor graph to do the optimization.
Non-linear factor base classes.
LevenbergMarquardtParams lmParams
const Symbol key2('v', 2)
LevenbergMarquardtParams params_
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics scale
Allow for arbitrary type in DSF.
std::vector< BinaryMeasurement< Unit3 >> TranslationEdges
Recovering translations in an epipolar graph when rotations are given.
std::map< KEY, Set > sets() const
return all sets, i.e. a partition of all elements
std::uint64_t Key
Integer nonlinear key type.
TranslationEdges relativeTranslations_
Values initalizeRandomly() const
Create random initial translations.
noiseModel::Base::shared_ptr SharedNoiseModel
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)