视觉约束部分
和前面的IMUFactor
类似,ProjectionFactor
也是一个继承自ceres::SizedCostFunction<2, 7, 7, 7, 1>
的类,同样,类的框架比较简单,重点仍然放在将基类中对应虚函数覆盖了的Evaluate
。
(注:factor
有因子的含义)
稍微提及一下类中的数据成员:
pts_i
和pts_j
:具体指什么含义?(分别为第l
个路标点在第i, j
个相机归一化相机坐标系中的观察到的坐标,
P
ˉ
l
c
i
\bar{P}^{c_i}_l
Pˉlci 和
P
ˉ
l
c
j
\bar{P}^{c_j}_l
Pˉlcj);
tangent_base
:正切平面上的任意两个正交基(在构造函数中通过计算?被赋值);
静态数据成员sqrt_info
和sum_t
:在何时被赋值的呢?
class ProjectionFactor : public ceres::SizedCostFunction<2, 7, 7, 7, 1>
{
public:
ProjectionFactor(const Eigen::Vector3d &_pts_i, const Eigen::Vector3d &_pts_j);
virtual bool Evaluate(double const *const *parameters, double *residuals, double **jacobians) const;
void check(double **parameters);
Eigen::Vector3d pts_i, pts_j;
Eigen::Matrix<double, 2, 3> tangent_base;
static Eigen::Matrix2d sqrt_info;
static double sum_t;
};
步入正题,ProjectionFactor
类中的Evaluate
成员函数:
优化变量:
[
p
b
i
w
,
q
b
i
w
]
,
[
p
b
j
w
,
q
b
j
w
]
,
[
p
c
b
,
q
c
b
]
,
λ
l
[p^w_{b_i}, q^w_{b_i}], [p^w_{b_j}, q^w_{b_j}], [p^b_c, q^b_c], \lambda_l
[pbiw,qbiw],[pbjw,qbjw],[pcb,qcb],λl
分别对应:[Pi, Qi], [Pj, Qj], [tic, qic], inv_dep_i
(此处的
λ
\lambda
λ表示什么含义?逆深度inv_dep_i
)(
w
,
b
w, b
w,b代表的坐标系具体指什么?)
解析中(27)式:
P
l
c
j
=
R
b
c
{
R
w
b
j
[
R
b
i
w
(
R
c
b
1
λ
l
P
ˉ
l
c
i
+
p
c
b
)
+
p
b
i
w
−
p
b
j
w
]
−
p
c
b
}
P^{c_j}_l=R^c_b\{R^{b_j}_w[R^w_{b_i}(R^b_c\frac{1}{\lambda_l}\bar{P}^{c_i}_l+p^b_c)+p^w_{b_i}-p^w_{b_j}]-p^b_c\}
Plcj=Rbc{Rwbj[Rbiw(Rcbλl1Pˉlci+pcb)+pbiw−pbjw]−pcb}
1
λ
l
P
ˉ
l
c
i
\frac{1}{\lambda_l}\bar{P}^{c_i}_l
λl1Pˉlci ==>Eigen::Vector3d pts_camera_i = pts_i / inv_dep_i;
(因此,pts_i
表示
P
ˉ
l
c
i
\bar{P}^{c_i}_l
Pˉlci,为第l
个路标点在第i
个相机归一化相机坐标系中的观察到的坐标);
(
R
c
b
∗
+
p
c
b
)
(R^b_c*+p^b_c)
(Rcb∗+pcb) ==>Eigen::Vector3d pts_imu_i = qic * pts_camera_i + tic;
(此处可以看出来,imu
与
b
b
b系是一个系?)
R
b
i
w
∗
+
p
b
i
w
R^w_{b_i}*+p^w_{b_i}
Rbiw∗+pbiw ==>Eigen::Vector3d pts_w = Qi * pts_imu_i + Pi;
R
w
b
j
(
∗
−
p
b
j
w
)
R^{b_j}_w(*-p^w_{b_j})
Rwbj(∗−pbjw) ==>Eigen::Vector3d pts_imu_j = Qj.inverse() * (pts_w - Pj);
R
b
c
(
∗
−
p
c
b
)
R^c_b(*-p^b_c)
Rbc(∗−pcb) ==>Eigen::Vector3d pts_camera_j = qic.inverse() * (pts_imu_j - tic);
因此,pts_camera_j
表示
P
l
c
j
P^{c_j}_l
Plcj,是由
P
ˉ
l
c
i
\bar{P}^{c_i}_l
Pˉlci计算得来的。
解析中(25)式:
r
c
(
z
^
l
c
j
,
X
)
=
[
b
1
⃗
b
2
⃗
]
(
P
l
c
j
∣
∣
P
l
c
j
∣
∣
−
P
ˉ
l
c
j
)
r_c(\hat{z}^{c_j}_l,X)=\begin{bmatrix}\vec{b_1}\\ \vec{b_2} \end{bmatrix}(\frac{P^{c_j}_l}{||P^{c_j}_l||}-\bar{P}^{c_j}_l)
rc(z^lcj,X)=[b1b2](∣∣Plcj∣∣Plcj−Pˉlcj)
residual = tangent_base * (pts_camera_j.normalized() - pts_j.normalized());
residual = sqrt_info * residual;
最后,计算Jacobian,解析中(28)式:
注:此处解析上有一些矩阵维数上的错误,应该为
3
×
∗
3\times *
3×∗,而非
2
×
∗
2\times *
2×∗。
以其中一个为例,分析公式与代码对应关系:
J
[
0
]
2
×
7
=
[
∂
r
c
∂
p
b
i
w
,
∂
r
c
∂
q
b
i
w
]
J[0]^{2\times 7}=[\frac{\partial r_c}{\partial p^w_{b_i}}, \frac{\partial r_c}{\partial q^w_{b_i}}]
J[0]2×7=[∂pbiw∂rc,∂qbiw∂rc]
代码中首先定义了一个jaco_i
为
3
×
6
3\times 6
3×6,然后用一个reduce
2
×
3
2\times 3
2×3去乘,得到的
2
×
6
2\times 6
2×6的结果作为
J
[
0
]
J[0]
J[0]的左边6列,最后一列为0;具体如下:
Eigen::Matrix<double, 3, 6> jaco_i;
R
b
c
R
w
b
j
R^c_bR^{b_j}_w
RbcRwbj
jaco_i.leftCols<3>() = ric.transpose() * Rj.transpose();
−
R
b
c
R
w
b
j
R
b
i
w
(
R
c
b
1
λ
l
P
ˉ
l
c
i
+
p
c
b
)
-R^c_bR^{b_j}_wR^w_{b_i}(R^b_c\frac{1}{\lambda_l}\bar{P}^{c_i}_l+p^b_c)
−RbcRwbjRbiw(Rcbλl1Pˉlci+pcb)
jaco_i.rightCols<3>() = ric.transpose() * Rj.transpose() * Ri * -Utility::skewSymmetric(pts_imu_i);
Eigen::Matrix<double, 2, 3> reduce(2, 3);
reduce = tangent_base * norm_jaco;
此处norm_jaco
表达什么含义?对应公式?
reduce = sqrt_info * reduce;
Eigen::Map
的用法?
Eigen::Map<Eigen::Matrix<double, 2, 7, Eigen::RowMajor>> jacobian_pose_i(jacobians[0]);
jacobian_pose_i.leftCols<6>() = reduce * jaco_i;
jacobian_pose_i.rightCols<1>().setZero();
J [ 1 ] 2 × 7 J[1]^{2\times 7} J[1]2×7、 J [ 2 ] 2 × 7 J[2]^{2\times 7} J[2]2×7和 J [ 3 ] 2 × 1 J[3]^{2\times 1} J[3]2×1的计算类似。
至此,视觉约束暂时告一段落。
bool ProjectionFactor::Evaluate(double const *const *parameters, double *residuals, double **jacobians) const
{
TicToc tic_toc;
Eigen::Vector3d Pi(parameters[0][0], parameters[0][1], parameters[0][2]);
Eigen::Quaterniond Qi(parameters[0][6], parameters[0][3], parameters[0][4], parameters[0][5]);
Eigen::Vector3d Pj(parameters[1][0], parameters[1][1], parameters[1][2]);
Eigen::Quaterniond Qj(parameters[1][6], parameters[1][3], parameters[1][4], parameters[1][5]);
Eigen::Vector3d tic(parameters[2][0], parameters[2][1], parameters[2][2]);
Eigen::Quaterniond qic(parameters[2][6], parameters[2][3], parameters[2][4], parameters[2][5]);
double inv_dep_i = parameters[3][0];
Eigen::Vector3d pts_camera_i = pts_i / inv_dep_i;
Eigen::Vector3d pts_imu_i = qic * pts_camera_i + tic;
Eigen::Vector3d pts_w = Qi * pts_imu_i + Pi;
Eigen::Vector3d pts_imu_j = Qj.inverse() * (pts_w - Pj);
Eigen::Vector3d pts_camera_j = qic.inverse() * (pts_imu_j - tic);
Eigen::Map<Eigen::Vector2d> residual(residuals);
#ifdef UNIT_SPHERE_ERROR
residual = tangent_base * (pts_camera_j.normalized() - pts_j.normalized());
#else
double dep_j = pts_camera_j.z();
residual = (pts_camera_j / dep_j).head<2>() - pts_j.head<2>();
#endif
residual = sqrt_info * residual;
if (jacobians)
{
Eigen::Matrix3d Ri = Qi.toRotationMatrix();
Eigen::Matrix3d Rj = Qj.toRotationMatrix();
Eigen::Matrix3d ric = qic.toRotationMatrix();
Eigen::Matrix<double, 2, 3> reduce(2, 3);
#ifdef UNIT_SPHERE_ERROR
double norm = pts_camera_j.norm();
Eigen::Matrix3d norm_jaco;
double x1, x2, x3;
x1 = pts_camera_j(0);
x2 = pts_camera_j(1);
x3 = pts_camera_j(2);
norm_jaco << 1.0 / norm - x1 * x1 / pow(norm, 3), - x1 * x2 / pow(norm, 3), - x1 * x3 / pow(norm, 3),
- x1 * x2 / pow(norm, 3), 1.0 / norm - x2 * x2 / pow(norm, 3), - x2 * x3 / pow(norm, 3),
- x1 * x3 / pow(norm, 3), - x2 * x3 / pow(norm, 3), 1.0 / norm - x3 * x3 / pow(norm, 3);
reduce = tangent_base * norm_jaco;
#else
reduce << 1. / dep_j, 0, -pts_camera_j(0) / (dep_j * dep_j),
0, 1. / dep_j, -pts_camera_j(1) / (dep_j * dep_j);
#endif
reduce = sqrt_info * reduce;
if (jacobians[0])
{
Eigen::Map<Eigen::Matrix<double, 2, 7, Eigen::RowMajor>> jacobian_pose_i(jacobians[0]);
Eigen::Matrix<double, 3, 6> jaco_i;
jaco_i.leftCols<3>() = ric.transpose() * Rj.transpose();
jaco_i.rightCols<3>() = ric.transpose() * Rj.transpose() * Ri * -Utility::skewSymmetric(pts_imu_i);
jacobian_pose_i.leftCols<6>() = reduce * jaco_i;
jacobian_pose_i.rightCols<1>().setZero();
}
if (jacobians[1])
{
Eigen::Map<Eigen::Matrix<double, 2, 7, Eigen::RowMajor>> jacobian_pose_j(jacobians[1]);
Eigen::Matrix<double, 3, 6> jaco_j;
jaco_j.leftCols<3>() = ric.transpose() * -Rj.transpose();
jaco_j.rightCols<3>() = ric.transpose() * Utility::skewSymmetric(pts_imu_j);
jacobian_pose_j.leftCols<6>() = reduce * jaco_j;
jacobian_pose_j.rightCols<1>().setZero();
}
if (jacobians[2])
{
Eigen::Map<Eigen::Matrix<double, 2, 7, Eigen::RowMajor>> jacobian_ex_pose(jacobians[2]);
Eigen::Matrix<double, 3, 6> jaco_ex;
jaco_ex.leftCols<3>() = ric.transpose() * (Rj.transpose() * Ri - Eigen::Matrix3d::Identity());
Eigen::Matrix3d tmp_r = ric.transpose() * Rj.transpose() * Ri * ric;
jaco_ex.rightCols<3>() = -tmp_r * Utility::skewSymmetric(pts_camera_i) + Utility::skewSymmetric(tmp_r * pts_camera_i) +
Utility::skewSymmetric(ric.transpose() * (Rj.transpose() * (Ri * tic + Pi - Pj) - tic));
jacobian_ex_pose.leftCols<6>() = reduce * jaco_ex;
jacobian_ex_pose.rightCols<1>().setZero();
}
if (jacobians[3])
{
Eigen::Map<Eigen::Vector2d> jacobian_feature(jacobians[3]);
#if 1
jacobian_feature = reduce * ric.transpose() * Rj.transpose() * Ri * ric * pts_i * -1.0 / (inv_dep_i * inv_dep_i);
#else
jacobian_feature = reduce * ric.transpose() * Rj.transpose() * Ri * ric * pts_i;
#endif
}
}
sum_t += tic_toc.toc();
return true;
}