move values from params to run, remove params struct

release/4.3a0
Akshay Krishnan 2022-05-09 22:46:16 -07:00
parent 3b77df652c
commit e17eddf99f
4 changed files with 41 additions and 41 deletions

View File

@ -134,15 +134,15 @@ void TranslationRecovery::addPrior(
Values TranslationRecovery::initializeRandomly( Values TranslationRecovery::initializeRandomly(
const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations, const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations,
std::mt19937 *rng) const { std::mt19937 *rng, const Values &initialValues) const {
uniform_real_distribution<double> randomVal(-1, 1); uniform_real_distribution<double> randomVal(-1, 1);
// Create a lambda expression that checks whether value exists and randomly // Create a lambda expression that checks whether value exists and randomly
// initializes if not. // initializes if not.
Values initial; Values initial;
auto insert = [&](Key j) { auto insert = [&](Key j) {
if (initial.exists(j)) return; if (initial.exists(j)) return;
if (params_.initial.exists(j)) { if (initialValues.exists(j)) {
initial.insert<Point3>(j, params_.initial.at<Point3>(j)); initial.insert<Point3>(j, initialValues.at<Point3>(j));
} else { } else {
initial.insert<Point3>( initial.insert<Point3>(
j, Point3(randomVal(*rng), randomVal(*rng), randomVal(*rng))); j, Point3(randomVal(*rng), randomVal(*rng), randomVal(*rng)));
@ -159,13 +159,16 @@ Values TranslationRecovery::initializeRandomly(
} }
Values TranslationRecovery::initializeRandomly( Values TranslationRecovery::initializeRandomly(
const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations) const { const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations,
return initializeRandomly(relativeTranslations, &kRandomNumberGenerator); const Values &initialValues) const {
return initializeRandomly(relativeTranslations, &kRandomNumberGenerator,
initialValues);
} }
Values TranslationRecovery::run( Values TranslationRecovery::run(
const TranslationEdges &relativeTranslations, const double scale, const TranslationEdges &relativeTranslations, const double scale,
const std::vector<BinaryMeasurement<Point3>> &betweenTranslations) const { const std::vector<BinaryMeasurement<Point3>> &betweenTranslations,
const Values &initialValues) const {
// Find edges that have a zero-translation, and recompute relativeTranslations // Find edges that have a zero-translation, and recompute relativeTranslations
// and betweenTranslations by retaining only one node for every zero-edge. // and betweenTranslations by retaining only one node for every zero-edge.
DSFMap<Key> sameTranslationDSFMap = DSFMap<Key> sameTranslationDSFMap =
@ -184,7 +187,8 @@ Values TranslationRecovery::run(
&graph); &graph);
// Uses initial values from params if provided. // Uses initial values from params if provided.
Values initial = initializeRandomly(nonzeroRelativeTranslations); Values initial =
initializeRandomly(nonzeroRelativeTranslations, initialValues);
// If there are no valid edges, but zero-distance edges exist, initialize one // If there are no valid edges, but zero-distance edges exist, initialize one
// of the nodes in a connected component of zero-distance edges. // of the nodes in a connected component of zero-distance edges.
@ -195,7 +199,7 @@ Values TranslationRecovery::run(
} }
} }
LevenbergMarquardtOptimizer lm(graph, initial, params_.lmParams); LevenbergMarquardtOptimizer lm(graph, initial, lmParams_);
Values result = lm.optimize(); Values result = lm.optimize();
return addSameTranslationNodes(result, sameTranslationDSFMap); return addSameTranslationNodes(result, sameTranslationDSFMap);
} }

View File

@ -28,15 +28,6 @@
namespace gtsam { namespace gtsam {
// Parameters for the Translation Recovery problem.
struct TranslationRecoveryParams {
// LevenbergMarquardtParams for optimization.
LevenbergMarquardtParams lmParams;
// Initial values, random intialization will be used if not provided.
Values initial;
};
// Set up an optimization problem for the unknown translations Ti in the world // Set up an optimization problem for the unknown translations Ti in the world
// coordinate frame, given the known camera attitudes wRi with respect to the // coordinate frame, given the known camera attitudes wRi with respect to the
// world frame, and a set of (noisy) translation directions of type Unit3, // world frame, and a set of (noisy) translation directions of type Unit3,
@ -67,16 +58,16 @@ class TranslationRecovery {
TranslationEdges relativeTranslations_; TranslationEdges relativeTranslations_;
// Parameters. // Parameters.
TranslationRecoveryParams params_; LevenbergMarquardtParams lmParams_;
public: public:
/** /**
* @brief Construct a new Translation Recovery object * @brief Construct a new Translation Recovery object
* *
* @param params parameters for the recovery problem. * @param lmParams parameters for optimization.
*/ */
TranslationRecovery(const TranslationRecoveryParams &params) TranslationRecovery(const LevenbergMarquardtParams &lmParams)
: params_(params) {} : lmParams_(lmParams) {}
/** /**
* @brief Default constructor. * @brief Default constructor.
@ -94,7 +85,11 @@ class TranslationRecovery {
const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations) const; const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations) const;
/** /**
* @brief Add priors on ednpoints of first measurement edge. * @brief Add 3 factors to the graph:
* - A prior on the first point to lie at (0, 0, 0)
* - If betweenTranslations is non-empty, between factors provided by it.
* - If betweenTranslations is empty, a prior on scale of the first
* relativeTranslations edge.
* *
* @param relativeTranslations unit translation directions between * @param relativeTranslations unit translation directions between
* translations to be estimated * translations to be estimated
@ -113,28 +108,29 @@ class TranslationRecovery {
noiseModel::Isotropic::Sigma(3, 0.01)) const; noiseModel::Isotropic::Sigma(3, 0.01)) const;
/** /**
* @brief Create random initial translations. Uses inial values from params if * @brief Create random initial translations.
* provided.
* *
* @param relativeTranslations unit translation directions between * @param relativeTranslations unit translation directions between
* translations to be estimated * translations to be estimated
* @param rng random number generator * @param rng random number generator
* @param intialValues (optional) initial values from a prior
* @return Values * @return Values
*/ */
Values initializeRandomly( Values initializeRandomly(
const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations, const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations,
std::mt19937 *rng) const; std::mt19937 *rng, const Values &initialValues = Values()) const;
/** /**
* @brief Version of initializeRandomly with a fixed seed. Uses initial values * @brief Version of initializeRandomly with a fixed seed.
* from params if provided.
* *
* @param relativeTranslations unit translation directions between * @param relativeTranslations unit translation directions between
* translations to be estimated * translations to be estimated
* @param initialValues (optional) initial values from a prior
* @return Values * @return Values
*/ */
Values initializeRandomly( Values initializeRandomly(
const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations) const; const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations,
const Values &initialValues = Values()) const;
/** /**
* @brief Build and optimize factor graph. * @brief Build and optimize factor graph.
@ -146,12 +142,14 @@ class TranslationRecovery {
* The scale is only used if betweenTranslations is empty. * The scale is only used if betweenTranslations is empty.
* @param betweenTranslations relative translations (with scale) between 2 * @param betweenTranslations relative translations (with scale) between 2
* points in world coordinate frame known a priori. * points in world coordinate frame known a priori.
* @param initialValues intial values for optimization. Initializes randomly
* if not provided.
* @return Values * @return Values
*/ */
Values run(const TranslationEdges &relativeTranslations, Values run(
const double scale = 1.0, const TranslationEdges &relativeTranslations, const double scale = 1.0,
const std::vector<BinaryMeasurement<Point3>> &betweenTranslations = const std::vector<BinaryMeasurement<Point3>> &betweenTranslations = {},
{}) const; const Values &initialValues = Values()) const;
/** /**
* @brief Simulate translation direction measurements * @brief Simulate translation direction measurements

View File

@ -262,14 +262,9 @@ class MFAS {
}; };
#include <gtsam/sfm/TranslationRecovery.h> #include <gtsam/sfm/TranslationRecovery.h>
class TranslationRecoveryParams {
gtsam::LevenbergMarquardtParams lmParams;
gtsam::Values initial;
TranslationRecoveryParams();
};
class TranslationRecovery { class TranslationRecovery {
TranslationRecovery(const gtsam::TranslationRecoveryParams& lmParams); TranslationRecovery(const gtsam::LevenbergMarquardtParams& lmParams);
TranslationRecovery(); // default params. TranslationRecovery(); // default params.
void addPrior(const gtsam::BinaryMeasurementsUnit3& relativeTranslations, void addPrior(const gtsam::BinaryMeasurementsUnit3& relativeTranslations,
const double scale, const double scale,
@ -282,6 +277,11 @@ class TranslationRecovery {
gtsam::NonlinearFactorGraph @graph) const; gtsam::NonlinearFactorGraph @graph) const;
gtsam::NonlinearFactorGraph buildGraph( gtsam::NonlinearFactorGraph buildGraph(
const gtsam::BinaryMeasurementsUnit3& relativeTranslations) const; const gtsam::BinaryMeasurementsUnit3& relativeTranslations) const;
gtsam::Values run(const gtsam::BinaryMeasurementsUnit3& relativeTranslations,
const double scale,
const gtsam::BinaryMeasurementsPoint3& betweenTranslations,
const gtsam::Values& initialValues) const;
// default random initial values
gtsam::Values run( gtsam::Values run(
const gtsam::BinaryMeasurementsUnit3& relativeTranslations, const gtsam::BinaryMeasurementsUnit3& relativeTranslations,
const double scale, const double scale,

View File

@ -46,10 +46,8 @@ class TestTranslationRecovery(unittest.TestCase):
# Set verbosity to Silent for tests # Set verbosity to Silent for tests
lmParams = gtsam.LevenbergMarquardtParams() lmParams = gtsam.LevenbergMarquardtParams()
lmParams.setVerbosityLM("silent") lmParams.setVerbosityLM("silent")
params = gtsam.TranslationRecoveryParams()
params.lmParams = lmParams
algorithm = gtsam.TranslationRecovery(params) algorithm = gtsam.TranslationRecovery(lmParams)
scale = 2.0 scale = 2.0
result = algorithm.run(measurements, scale) result = algorithm.run(measurements, scale)