Move smart projection factor
parent
e19f3c5902
commit
87f5818776
|
@ -16,7 +16,7 @@
|
||||||
* Author: cbeall3
|
* Author: cbeall3
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <gtsam_unstable/geometry/triangulation.h>
|
#include <gtsam/geometry/triangulation.h>
|
||||||
#include <gtsam/geometry/Cal3Bundler.h>
|
#include <gtsam/geometry/Cal3Bundler.h>
|
||||||
#include <CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
|
@ -16,7 +16,7 @@
|
||||||
* @author Chris Beall
|
* @author Chris Beall
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <gtsam_unstable/geometry/triangulation.h>
|
#include <gtsam/geometry/triangulation.h>
|
||||||
|
|
||||||
#include <gtsam/geometry/PinholeCamera.h>
|
#include <gtsam/geometry/PinholeCamera.h>
|
||||||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
|
@ -18,8 +18,8 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <gtsam_unstable/base/dllexport.h>
|
|
||||||
#include <gtsam_unstable/geometry/TriangulationFactor.h>
|
#include <gtsam/geometry/TriangulationFactor.h>
|
||||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||||
#include <gtsam/inference/Symbol.h>
|
#include <gtsam/inference/Symbol.h>
|
||||||
#include <gtsam/slam/PriorFactor.h>
|
#include <gtsam/slam/PriorFactor.h>
|
||||||
|
@ -52,7 +52,7 @@ public:
|
||||||
* @param rank_tol SVD rank tolerance
|
* @param rank_tol SVD rank tolerance
|
||||||
* @return Triangulated Point3
|
* @return Triangulated Point3
|
||||||
*/
|
*/
|
||||||
GTSAM_UNSTABLE_EXPORT Point3 triangulateDLT(
|
GTSAM_EXPORT Point3 triangulateDLT(
|
||||||
const std::vector<Matrix>& projection_matrices,
|
const std::vector<Matrix>& projection_matrices,
|
||||||
const std::vector<Point2>& measurements, double rank_tol);
|
const std::vector<Point2>& measurements, double rank_tol);
|
||||||
|
|
||||||
|
@ -120,7 +120,7 @@ std::pair<NonlinearFactorGraph, Values> triangulationGraph(
|
||||||
* @param landmarkKey to refer to landmark
|
* @param landmarkKey to refer to landmark
|
||||||
* @return refined Point3
|
* @return refined Point3
|
||||||
*/
|
*/
|
||||||
GTSAM_UNSTABLE_EXPORT Point3 optimize(const NonlinearFactorGraph& graph,
|
GTSAM_EXPORT Point3 optimize(const NonlinearFactorGraph& graph,
|
||||||
const Values& values, Key landmarkKey);
|
const Values& values, Key landmarkKey);
|
||||||
|
|
||||||
/**
|
/**
|
|
@ -6,7 +6,7 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
#include <gtsam_unstable/slam/JacobianSchurFactor.h>
|
#include <gtsam/slam/JacobianSchurFactor.h>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
/**
|
/**
|
|
@ -5,7 +5,7 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
#include "gtsam_unstable/slam/JacobianSchurFactor.h"
|
#include "gtsam/slam/JacobianSchurFactor.h"
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
/**
|
/**
|
|
@ -21,11 +21,10 @@
|
||||||
|
|
||||||
#include "SmartFactorBase.h"
|
#include "SmartFactorBase.h"
|
||||||
|
|
||||||
#include <gtsam_unstable/geometry/triangulation.h>
|
#include <gtsam/geometry/triangulation.h>
|
||||||
#include <gtsam/geometry/Pose3.h>
|
#include <gtsam/geometry/Pose3.h>
|
||||||
#include <gtsam/inference/Symbol.h>
|
#include <gtsam/inference/Symbol.h>
|
||||||
#include <gtsam/slam/dataset.h>
|
#include <gtsam/slam/dataset.h>
|
||||||
#include <gtsam_unstable/geometry/triangulation.h>
|
|
||||||
|
|
||||||
#include <boost/optional.hpp>
|
#include <boost/optional.hpp>
|
||||||
#include <boost/make_shared.hpp>
|
#include <boost/make_shared.hpp>
|
|
@ -35,7 +35,7 @@
|
||||||
#include <gtsam/inference/Symbol.h>
|
#include <gtsam/inference/Symbol.h>
|
||||||
#include <gtsam/slam/dataset.h>
|
#include <gtsam/slam/dataset.h>
|
||||||
|
|
||||||
#include <gtsam_unstable/slam/SmartProjectionPoseFactor.h>
|
#include <gtsam/slam/SmartProjectionPoseFactor.h>
|
||||||
|
|
||||||
#include <string>
|
#include <string>
|
||||||
#include <fstream>
|
#include <fstream>
|
||||||
|
|
Loading…
Reference in New Issue