resectionsolver.h
Go to the documentation of this file.
00001 
00018 #ifndef RESECTIONSOLVER_H
00019 #define RESECTIONSOLVER_H
00020 #include <vector>
00021 
00022 #include <MathHelpers/Resectionsolver/feasibilitychecker.h>
00023 #include <calibration_object.h>
00024 #ifndef Q_MOC_RUN
00025 #include <Eigen/Dense>
00026 #include <boost/shared_ptr.hpp>
00027 #endif
00028 
00029 class ResectionSolver
00030 {
00031 public:
00032     ResectionSolver(boost::shared_ptr<Calibration_Object> calibrationObject, boost::shared_ptr<FeasibilityChecker> feasibilityChecker);
00033     unsigned int solve(const Eigen::Vector2d& base_A, const Eigen::Vector2d& base_B, const Eigen::Vector2d& base_C);
00034     Eigen::Matrix4d calculateTransformationMatrix(const Eigen::Vector2d& base_A, const Eigen::Vector2d& base_B, const Eigen::Vector2d& base_C, const Eigen::Vector3d& solution);
00035     std::vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > solutions;
00036     std::vector<double> solutions_a;
00037     std::vector<double> solutions_b;
00038     std::vector<double> solutions_c;
00039 
00040     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00041 protected:
00042     double q_0, q_1, q_2, q_3, q_4;
00043     boost::shared_ptr<Calibration_Object> calibrationObject;
00044     double K_1, K_2;
00045 
00046     boost::shared_ptr<FeasibilityChecker> feasibilityChecker;
00047 
00048     int solve_for_lengths(double side_A, double side_B, double side_C);
00049     unsigned int solve_for_lengths_(double side_A, double side_B, double side_C);
00050     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);
00051 
00052 };
00053 
00054 #endif // RESECTIONSOLVER_H


asr_mild_calibration_tool
Author(s): Aumann Florian, Heller Florian, Meißner Pascal
autogenerated on Thu Jun 6 2019 21:22:44