-
Notifications
You must be signed in to change notification settings - Fork 43
/
Copy pathparametersse3.cpp
162 lines (131 loc) · 4.97 KB
/
parametersse3.cpp
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
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
#include "parametersse3.hpp"
template<>
bool ReprojectionErrorSE3XYZ<7>::Evaluate(const double * const *parameters, double *residuals, double **jacobians) const
{
Eigen::Map<const Quaterniond> quaterd(parameters[0]);
Eigen::Map<const Eigen::Vector3d> trans(parameters[0] + 4);
Eigen::Map<const Eigen::Vector3d> point(parameters[1]);
Eigen::Vector3d p = quaterd * point + trans;
double f_by_z = f / p[2];
residuals[0] = f_by_z * p[0] + cx - _observation_x;
residuals[1] = f_by_z * p[1] + cy - _observation_y;
Eigen::Matrix<double, 2, 3, Eigen::RowMajor> J_cam;
double f_by_zz = f_by_z / p[2];
J_cam << f_by_z, 0, - f_by_zz * p[0],
0, f_by_z, - f_by_zz * p[1];
if(jacobians != NULL)
{
if(jacobians[0] != NULL)
{
Eigen::Map<Eigen::Matrix<double, 2, 7, Eigen::RowMajor> > J_se3(jacobians[0]);
J_se3.setZero();
J_se3.block<2,3>(0,0) = - J_cam * skew(p);
J_se3.block<2,3>(0,3) = J_cam;
}
if(jacobians[1] != NULL)
{
Eigen::Map<Eigen::Matrix<double, 2, 3, Eigen::RowMajor> > J_point(jacobians[1]);
J_point = J_cam * quaterd.toRotationMatrix();
}
}
return true;
}
template<>
bool ReprojectionErrorSE3XYZ<6>::Evaluate(const double * const *parameters, double *residuals, double **jacobians) const
{
Eigen::Quaterniond quaterd = toQuaterniond(Eigen::Map<const Vector3d>(parameters[0]));
Eigen::Map<const Eigen::Vector3d> trans(parameters[0] + 3);
Eigen::Map<const Eigen::Vector3d> point(parameters[1]);
Eigen::Vector3d p = quaterd * point + trans;
double f_by_z = f / p[2];
residuals[0] = f_by_z * p[0] + cx - _observation_x;
residuals[1] = f_by_z * p[1] + cy - _observation_y;
Eigen::Matrix<double, 2, 3, Eigen::RowMajor> J_cam;
double f_by_zz = f_by_z / p[2];
J_cam << f_by_z, 0, - f_by_zz * p[0],
0, f_by_z, - f_by_zz * p[1];
if(jacobians != NULL)
{
if(jacobians[0] != NULL)
{
Eigen::Map<Eigen::Matrix<double, 2, 6, Eigen::RowMajor> > J_se3(jacobians[0]);
J_se3.block<2,3>(0,0) = - J_cam * skew(p);
J_se3.block<2,3>(0,3) = J_cam;
}
if(jacobians[1] != NULL)
{
Eigen::Map<Eigen::Matrix<double, 2, 3, Eigen::RowMajor> > J_point(jacobians[1]);
J_point = J_cam * quaterd.toRotationMatrix();
}
}
return true;
}
template<>
bool PoseSE3Parameterization<7>::Plus(const double *x, const double *delta, double *x_plus_delta) const
{
Eigen::Map<const Eigen::Vector3d> trans(x + 4);
SE3 se3_delta = SE3::exp(Eigen::Map<const Vector6d>(delta));
Eigen::Map<const Eigen::Quaterniond> quaterd(x);
Eigen::Map<Eigen::Quaterniond> quaterd_plus(x_plus_delta);
Eigen::Map<Eigen::Vector3d> trans_plus(x_plus_delta + 4);
quaterd_plus = se3_delta.rotation() * quaterd;
trans_plus = se3_delta.rotation() * trans + se3_delta.translation();
return true;
}
template<>
bool PoseSE3Parameterization<7>::ComputeJacobian(const double *x, double *jacobian) const
{
Eigen::Map<Eigen::Matrix<double, 7, 6, Eigen::RowMajor> > J(jacobian);
J.setZero();
J.block<6,6>(0, 0).setIdentity();
return true;
}
template<>
bool PoseSE3Parameterization<6>::Plus(const double *x, const double *delta, double *x_plus_delta) const
{
Eigen::Map<const Eigen::Vector3d> trans(x + 3);
SE3 se3_delta = SE3::exp(Eigen::Map<const Vector6d>(delta));
Quaterniond quaterd_plus = se3_delta.rotation() * toQuaterniond(Eigen::Map<const Vector3d>(x));
Eigen::Map<Vector3d> angles_plus(x_plus_delta);
angles_plus = toAngleAxis(quaterd_plus);
Eigen::Map<Eigen::Vector3d> trans_plus(x_plus_delta + 3);
trans_plus = se3_delta.rotation() * trans + se3_delta.translation();
return true;
}
template<>
bool PoseSE3Parameterization<6>::ComputeJacobian(const double *x, double *jacobian) const
{
Eigen::Map<Eigen::Matrix<double, 6, 6, Eigen::RowMajor> > J(jacobian);
J.setIdentity();
return true;
}
template<>
void PosePointParametersBlock<7>::getPose(int idx, Quaterniond &q, Vector3d &trans)
{
double* pose_ptr = values + idx * 7;
q = Map<const Quaterniond>(pose_ptr);
trans = Map<const Vector3d>(pose_ptr + 4);
}
template<>
void PosePointParametersBlock<7>::setPose(int idx, const Quaterniond &q, const Vector3d &trans)
{
double* pose_ptr = values + idx * 7;
Eigen::Map<Vector7d> pose(pose_ptr);
pose.head<4>() = Eigen::Vector4d(q.coeffs());
pose.tail<3>() = trans;
}
template<>
void PosePointParametersBlock<6>::getPose(int idx, Quaterniond &q, Vector3d &trans)
{
double* pose_ptr = values + idx * 6;
q = toQuaterniond(Vector3d(pose_ptr));
trans = Map<const Vector3d>(pose_ptr + 3);
}
template<>
void PosePointParametersBlock<6>::setPose(int idx, const Quaterniond &q, const Vector3d &trans)
{
double* pose_ptr = values + idx * 6;
Eigen::Map<Vector6d> pose(pose_ptr);
pose.head<3>() = toAngleAxis(q);
pose.tail<3>() = trans;
}