Go to the documentation of this file.
38 using namespace gtsam;
52 for (
const auto &edge : relativeTranslations) {
59 return sameTranslationDSF;
68 std::vector<BinaryMeasurement<T>> newEdges;
69 for (
const auto &edge :
edges) {
73 newEdges.emplace_back(
key1,
key2, edge.measured(), edge.noiseModel());
86 for (
const auto &optimizedAndDuplicateKeys : sameTranslationDSFMap.
sets()) {
87 Key optimizedKey = optimizedAndDuplicateKeys.first;
88 std::set<Key> duplicateKeys = optimizedAndDuplicateKeys.second;
90 for (
const Key duplicateKey : duplicateKeys) {
91 if (final_result.
exists(duplicateKey))
continue;
93 final_result.
at<
Point3>(optimizedKey));
105 for (
auto edge : relativeTranslations) {
106 if (use_bilinear_translation_factor_) {
108 edge.key1(), edge.key2(),
Symbol(
'S',
i), edge.measured(),
112 edge.key1(), edge.key2(), edge.measured(), edge.noiseModel());
125 auto edge = relativeTranslations.begin();
126 if (edge == relativeTranslations.end())
return;
131 if (betweenTranslations.empty()) {
133 edge->key2(),
scale * edge->measured().point3(), edge->noiseModel());
138 for (
auto prior_edge : betweenTranslations) {
140 prior_edge.key1(), prior_edge.key2(), prior_edge.measured(),
141 prior_edge.noiseModel());
148 std::mt19937 *
rng,
const Values &initialValues)
const {
149 uniform_real_distribution<double> randomVal(-1, 1);
165 for (
auto edge : relativeTranslations) {
170 for (
auto edge : betweenTranslations) {
175 if (use_bilinear_translation_factor_) {
176 for (
uint64_t i = 0;
i < relativeTranslations.size();
i++) {
186 const Values &initialValues)
const {
187 return initializeRandomly(relativeTranslations, betweenTranslations,
194 const Values &initialValues)
const {
201 const std::vector<BinaryMeasurement<Point3>> nonzeroBetweenTranslations =
209 addPrior(nonzeroRelativeTranslations,
scale, nonzeroBetweenTranslations,
214 nonzeroRelativeTranslations, nonzeroBetweenTranslations, initialValues);
218 if (
initial.empty() && !sameTranslationDSFMap.
sets().empty()) {
219 for (
const auto &optimizedAndDuplicateKeys : sameTranslationDSFMap.
sets()) {
220 Key optimizedKey = optimizedAndDuplicateKeys.first;
231 const Values &poses,
const vector<KeyPair> &
edges) {
234 for (
auto edge :
edges) {
239 const Unit3 w_aZb(Tb - Ta);
240 relativeTranslations.emplace_back(
a,
b, w_aZb, edgeNoiseModel);
242 return relativeTranslations;
const Symbol key1('v', 1)
Eigen::Matrix< double, 1, 1 > Vector1
virtual const Values & optimize()
DSFMap< Key > getSameTranslationDSFMap(const std::vector< BinaryMeasurement< Unit3 >> &relativeTranslations)
std::vector< BinaryMeasurement< Unit3 > > TranslationEdges
Binary factor for a relative translation direction measurement.
vector< MFAS::KeyPair > edges
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
bool equals(const Symbol &expected, double tol=0.0) const
Check equality.
NonlinearFactorGraph buildGraph(const std::vector< BinaryMeasurement< Unit3 >> &relativeTranslations) const
Build the factor graph to do the optimization.
std::vector< BinaryMeasurement< T > > removeSameTranslationNodes(const std::vector< BinaryMeasurement< T >> &edges, const DSFMap< Key > &sameTranslationDSFMap)
Values addSameTranslationNodes(const Values &result, const DSFMap< Key > &sameTranslationDSFMap)
Values initializeRandomly(const std::vector< BinaryMeasurement< Unit3 >> &relativeTranslations, const std::vector< BinaryMeasurement< Point3 >> &betweenTranslations, std::mt19937 *rng, const Values &initialValues=Values()) const
Create random initial translations.
const ValueType at(Key j) const
const Symbol key2('v', 2)
Allow for arbitrary type in DSF.
static std::mt19937 kRandomNumberGenerator(42)
std::map< KEY, Set > sets() const
return all sets, i.e. a partition of all elements
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
static TranslationEdges SimulateMeasurements(const Values &poses, const std::vector< KeyPair > &edges)
Simulate translation direction measurements.
noiseModel::Base::shared_ptr SharedNoiseModel
graph addPrior(1, Pose2(0, 0, 0), priorNoise)
void addPrior(const std::vector< BinaryMeasurement< Unit3 >> &relativeTranslations, const double scale, const std::vector< BinaryMeasurement< Point3 >> &betweenTranslations, NonlinearFactorGraph *graph, const SharedNoiseModel &priorNoiseModel=noiseModel::Isotropic::Sigma(3, 0.01)) const
Add 3 factors to the graph:
KEY find(const KEY &key) const
Given key, find the representative key for the set in which it lives.
void merge(const KEY &x, const KEY &y)
Merge two sets.
Non-linear factor base classes.
Recovering translations in an epipolar graph when rotations are given.
Values run(const TranslationEdges &relativeTranslations, const double scale=1.0, const std::vector< BinaryMeasurement< Point3 >> &betweenTranslations={}, const Values &initialValues=Values()) const
Build and optimize factor graph.
Factor Graph consisting of non-linear factors.
Common expressions for solving geometry/slam/sfm problems.
void insert(Key j, const Value &val)
static double scale(double x, double a, double b, double t1, double t2)
Scale x from [a, b] to [t1, t2].
The matrix class, also used for vectors and row-vectors.
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
unsigned __int64 uint64_t
Represents a 3D point on a unit sphere.
NonlinearFactorGraph graph
std::uint64_t Key
Integer nonlinear key type.
A non-templated config holding any types of Manifold-group elements.
3D Pose manifold SO(3) x R^3 and group SE(3)
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:18:01