resectionsolver.h
Go to the documentation of this file.
1 
18 #ifndef RESECTIONSOLVER_H
19 #define RESECTIONSOLVER_H
20 #include <vector>
21 
23 #include <calibration_object.h>
24 #ifndef Q_MOC_RUN
25 #include <Eigen/Dense>
26 #include <boost/shared_ptr.hpp>
27 #endif
28 
30 {
31 public:
33  unsigned int solve(const Eigen::Vector2d& base_A, const Eigen::Vector2d& base_B, const Eigen::Vector2d& base_C);
34  Eigen::Matrix4d calculateTransformationMatrix(const Eigen::Vector2d& base_A, const Eigen::Vector2d& base_B, const Eigen::Vector2d& base_C, const Eigen::Vector3d& solution);
35  std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > solutions;
36  std::vector<double> solutions_a;
37  std::vector<double> solutions_b;
38  std::vector<double> solutions_c;
39 
40  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
41 protected:
42  double q_0, q_1, q_2, q_3, q_4;
44  double K_1, K_2;
45 
47 
48  int solve_for_lengths(double side_A, double side_B, double side_C);
49  unsigned int solve_for_lengths_(double side_A, double side_B, double side_C);
50  Eigen::Vector3d solve_for_top(const Eigen::Vector2d& base_A, const Eigen::Vector2d& base_B, const Eigen::Vector2d& base_C, double length_AS, double length_BS, double length_CS);
51 
52 };
53 
54 #endif // RESECTIONSOLVER_H
boost::shared_ptr< Calibration_Object > calibrationObject
unsigned int solve_for_lengths_(double side_A, double side_B, double side_C)
int solve_for_lengths(double side_A, double side_B, double side_C)
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > solutions
Eigen::Matrix4d calculateTransformationMatrix(const Eigen::Vector2d &base_A, const Eigen::Vector2d &base_B, const Eigen::Vector2d &base_C, const Eigen::Vector3d &solution)
boost::shared_ptr< FeasibilityChecker > feasibilityChecker
unsigned int solve(const Eigen::Vector2d &base_A, const Eigen::Vector2d &base_B, const Eigen::Vector2d &base_C)
ResectionSolver(boost::shared_ptr< Calibration_Object > calibrationObject, boost::shared_ptr< FeasibilityChecker > feasibilityChecker)
std::vector< double > solutions_a
std::vector< double > solutions_b
Eigen::Vector3d solve_for_top(const Eigen::Vector2d &base_A, const Eigen::Vector2d &base_B, const Eigen::Vector2d &base_C, double length_AS, double length_BS, double length_CS)
std::vector< double > solutions_c


asr_mild_calibration_tool
Author(s): Aumann Florian, Heller Florian, Meißner Pascal
autogenerated on Mon Dec 2 2019 03:11:43