-
Notifications
You must be signed in to change notification settings - Fork 17
/
solver_WQ_helper.h
35 lines (29 loc) · 1.23 KB
/
solver_WQ_helper.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
// LibQPEP: A Library for Globally Optimal Solving Quadratic Pose Estimation Problems,
// It also gives highly accurate uncertainty description of the solutions.
//
// Author: Jin Wu
// Affiliation: Hong Kong University of Science and Technology (HKUST)
// Emails: [email protected]; [email protected]
// Reference: Wu, J., et al. (2022) Quadratic Pose Estimation Problems:
// Globally Optimal Solutions,
// Solvability/Observability Analysis,
// and Uncertainty Description.
// IEEE Transactions on Robotics.
// https://doi.org/10.1109/TRO.2022.3155880
#ifndef LIBQPEP_SOLVER_HELPER_H
#define LIBQPEP_SOLVER_HELPER_H
#include <time.h>
#include <iostream>
#include <vector>
#include <map>
#include <cassert>
#include <Eigen/Core>
#include <Eigen/LU>
#include <Eigen/Dense>
#include <Eigen/Geometry> // For Quaternion
#include <Eigen/Sparse>
#include "QPEP.h"
void data_func_solver_WQ_func(Eigen::SparseMatrix<double>& C1,
Eigen::MatrixXd& C2,
const Eigen::VectorXd& data);
#endif //LIBQPEP_SOLVER_HELPER_H