|
|
@ -50,7 +50,7 @@ Isometry3d CAMState::T_cam0_cam1 = Isometry3d::Identity();
|
|
|
|
|
|
|
|
|
|
|
|
// Static member variables in Feature class.
|
|
|
|
// Static member variables in Feature class.
|
|
|
|
FeatureIDType Feature::next_id = 0;
|
|
|
|
FeatureIDType Feature::next_id = 0;
|
|
|
|
double Feature::observation_noise = 0.05;
|
|
|
|
double Feature::observation_noise = 0.2;
|
|
|
|
Feature::OptimizationConfig Feature::optimization_config;
|
|
|
|
Feature::OptimizationConfig Feature::optimization_config;
|
|
|
|
|
|
|
|
|
|
|
|
map<int, double> MsckfVio::chi_squared_test_table;
|
|
|
|
map<int, double> MsckfVio::chi_squared_test_table;
|
|
|
@ -542,13 +542,14 @@ void MsckfVio::manageMovingWindow(
|
|
|
|
cv_bridge::CvImageConstPtr cam1_img_ptr = cv_bridge::toCvShare(cam1_img,
|
|
|
|
cv_bridge::CvImageConstPtr cam1_img_ptr = cv_bridge::toCvShare(cam1_img,
|
|
|
|
sensor_msgs::image_encodings::MONO8);
|
|
|
|
sensor_msgs::image_encodings::MONO8);
|
|
|
|
|
|
|
|
|
|
|
|
image_handler::undistortImage(cam0_img_ptr->image, cam0_img_ptr->image, cam0.distortion_model, cam0.intrinsics, cam0.distortion_coeffs);
|
|
|
|
cv::Mat newImage0;
|
|
|
|
image_handler::undistortImage(cam1_img_ptr->image, cam1_img_ptr->image, cam1.distortion_model, cam1.intrinsics, cam1.distortion_coeffs);
|
|
|
|
cv::Mat newImage1;
|
|
|
|
|
|
|
|
image_handler::undistortImage(cam0_img_ptr->image, newImage0, cam0.distortion_model, cam0.intrinsics, cam0.distortion_coeffs);
|
|
|
|
|
|
|
|
image_handler::undistortImage(cam1_img_ptr->image, newImage1, cam1.distortion_model, cam1.intrinsics, cam1.distortion_coeffs);
|
|
|
|
|
|
|
|
|
|
|
|
// save image information into moving window
|
|
|
|
// save image information into moving window
|
|
|
|
cam0.moving_window[state_server.imu_state.id].image = cam0_img_ptr->image.clone();
|
|
|
|
cam0.moving_window[state_server.imu_state.id].image = newImage0.clone();
|
|
|
|
cam1.moving_window[state_server.imu_state.id].image = cam1_img_ptr->image.clone();
|
|
|
|
cam1.moving_window[state_server.imu_state.id].image = newImage1.clone();
|
|
|
|
|
|
|
|
|
|
|
|
cv::Mat xder;
|
|
|
|
cv::Mat xder;
|
|
|
|
cv::Mat yder;
|
|
|
|
cv::Mat yder;
|
|
|
@ -1561,9 +1562,9 @@ void MsckfVio::twodotFeatureJacobian(
|
|
|
|
bool MsckfVio::PhotometricPatchPointResidual(
|
|
|
|
bool MsckfVio::PhotometricPatchPointResidual(
|
|
|
|
const StateIDType& cam_state_id,
|
|
|
|
const StateIDType& cam_state_id,
|
|
|
|
const Feature& feature,
|
|
|
|
const Feature& feature,
|
|
|
|
VectorXd& r)
|
|
|
|
VectorXd& r, int patchsize)
|
|
|
|
{
|
|
|
|
{
|
|
|
|
VectorXd r_photo = VectorXd::Zero(2*N*N);
|
|
|
|
VectorXd r_photo = VectorXd::Zero(2*patchsize*patchsize);
|
|
|
|
int count = 0;
|
|
|
|
int count = 0;
|
|
|
|
const CAMState& cam_state = state_server.cam_states[cam_state_id];
|
|
|
|
const CAMState& cam_state = state_server.cam_states[cam_state_id];
|
|
|
|
|
|
|
|
|
|
|
@ -1580,6 +1581,7 @@ bool MsckfVio::PhotometricPatchPointResidual(
|
|
|
|
estimate_photo_z_c0.push_back (estimate_irradiance_j);// *
|
|
|
|
estimate_photo_z_c0.push_back (estimate_irradiance_j);// *
|
|
|
|
//estimated_illumination.frame_gain * estimated_illumination.feature_gain +
|
|
|
|
//estimated_illumination.frame_gain * estimated_illumination.feature_gain +
|
|
|
|
//estimated_illumination.frame_bias + estimated_illumination.feature_bias);
|
|
|
|
//estimated_illumination.frame_bias + estimated_illumination.feature_bias);
|
|
|
|
|
|
|
|
|
|
|
|
feature.estimate_FrameIrradiance(cam_state, cam_state_id, cam1, estimate_irradiance, estimated_illumination);
|
|
|
|
feature.estimate_FrameIrradiance(cam_state, cam_state_id, cam1, estimate_irradiance, estimated_illumination);
|
|
|
|
for (auto& estimate_irradiance_j : estimate_irradiance)
|
|
|
|
for (auto& estimate_irradiance_j : estimate_irradiance)
|
|
|
|
estimate_photo_z_c1.push_back (estimate_irradiance_j);// *
|
|
|
|
estimate_photo_z_c1.push_back (estimate_irradiance_j);// *
|
|
|
@ -1596,14 +1598,31 @@ bool MsckfVio::PhotometricPatchPointResidual(
|
|
|
|
|
|
|
|
|
|
|
|
cv::Mat current_image_c0 = cam0.moving_window.find(cam_state_id)->second.image;
|
|
|
|
cv::Mat current_image_c0 = cam0.moving_window.find(cam_state_id)->second.image;
|
|
|
|
cv::Mat current_image_c1 = cam1.moving_window.find(cam_state_id)->second.image;
|
|
|
|
cv::Mat current_image_c1 = cam1.moving_window.find(cam_state_id)->second.image;
|
|
|
|
for(int i = 0; i<N; i++) {
|
|
|
|
for(int i = 0; i<patchsize; i++) {
|
|
|
|
for(int j = 0; j<N ; j++) {
|
|
|
|
for(int j = 0; j<patchsize; j++) {
|
|
|
|
true_irradiance_c0.push_back(feature.PixelIrradiance(cv::Point2f(p_f_c0.x + (i-(N-1)/2), p_f_c0.y + (j-(N-1)/2)), current_image_c0));
|
|
|
|
true_irradiance_c0.push_back(feature.PixelIrradiance(cv::Point2f(p_f_c0.x + (i-(patchsize-1)/2), p_f_c0.y + (j-(patchsize-1)/2)), current_image_c0));
|
|
|
|
true_irradiance_c1.push_back(feature.PixelIrradiance(cv::Point2f(p_f_c1.x + (i-(N-1)/2), p_f_c1.y + (j-(N-1)/2)), current_image_c1));
|
|
|
|
true_irradiance_c1.push_back(feature.PixelIrradiance(cv::Point2f(p_f_c1.x + (i-(patchsize-1)/2), p_f_c1.y + (j-(patchsize-1)/2)), current_image_c1));
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
// get residual
|
|
|
|
std::vector<Eigen::Vector3d> new_anchorPatch_3d;
|
|
|
|
|
|
|
|
if (patchsize == 3 and N == 5)
|
|
|
|
|
|
|
|
{
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[6]);
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[7]);
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[8]);
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[11]);
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[12]);
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[13]);
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[16]);
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[17]);
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[18]);
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
else
|
|
|
|
|
|
|
|
{
|
|
|
|
|
|
|
|
new_anchorPatch_3d = feature.anchorPatch_3d;
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
for(auto point : feature.anchorPatch_3d)
|
|
|
|
for(auto point : feature.anchorPatch_3d)
|
|
|
|
{
|
|
|
|
{
|
|
|
|
|
|
|
|
|
|
|
@ -1629,6 +1648,7 @@ bool MsckfVio::PhotometricPatchPointResidual(
|
|
|
|
count++;
|
|
|
|
count++;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
r = r_photo;
|
|
|
|
r = r_photo;
|
|
|
|
|
|
|
|
|
|
|
|
return true;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
@ -1639,6 +1659,7 @@ bool MsckfVio::PhotometricPatchPointJacobian(
|
|
|
|
const Feature& feature,
|
|
|
|
const Feature& feature,
|
|
|
|
Eigen::Vector3d point,
|
|
|
|
Eigen::Vector3d point,
|
|
|
|
int count,
|
|
|
|
int count,
|
|
|
|
|
|
|
|
int patchsize,
|
|
|
|
Eigen::Matrix<double, 2, 1>& H_rhoj,
|
|
|
|
Eigen::Matrix<double, 2, 1>& H_rhoj,
|
|
|
|
Eigen::Matrix<double, 2, 6>& H_plj,
|
|
|
|
Eigen::Matrix<double, 2, 6>& H_plj,
|
|
|
|
Eigen::Matrix<double, 2, 6>& H_pAj,
|
|
|
|
Eigen::Matrix<double, 2, 6>& H_pAj,
|
|
|
@ -1723,11 +1744,11 @@ bool MsckfVio::PhotometricPatchPointJacobian(
|
|
|
|
// d{}^Gp_P{ij} / \rho_i
|
|
|
|
// d{}^Gp_P{ij} / \rho_i
|
|
|
|
double rho = feature.anchor_rho;
|
|
|
|
double rho = feature.anchor_rho;
|
|
|
|
// Isometry T_anchor_w takes a vector in anchor frame to world frame
|
|
|
|
// Isometry T_anchor_w takes a vector in anchor frame to world frame
|
|
|
|
dGpj_drhoj = -feature.T_anchor_w.linear() * Eigen::Vector3d(feature.anchorPatch_ideal[(N*N-1)/2].x/(rho*rho), feature.anchorPatch_ideal[(N*N-1)/2].y/(rho*rho), 1/(rho*rho));
|
|
|
|
dGpj_drhoj = -feature.T_anchor_w.linear() * Eigen::Vector3d(feature.anchorPatch_ideal[(patchsize*patchsize-1)/2].x/(rho*rho), feature.anchorPatch_ideal[(patchsize*patchsize-1)/2].y/(rho*rho), 1/(rho*rho));
|
|
|
|
|
|
|
|
|
|
|
|
dGpj_XpAj.block<3, 3>(0, 0) = - feature.T_anchor_w.linear()
|
|
|
|
dGpj_XpAj.block<3, 3>(0, 0) = - feature.T_anchor_w.linear()
|
|
|
|
* skewSymmetric(Eigen::Vector3d(feature.anchorPatch_ideal[(N*N-1)/2].x/(rho),
|
|
|
|
* skewSymmetric(Eigen::Vector3d(feature.anchorPatch_ideal[(patchsize*patchsize-1)/2].x/(rho),
|
|
|
|
feature.anchorPatch_ideal[(N*N-1)/2].y/(rho),
|
|
|
|
feature.anchorPatch_ideal[(patchsize*patchsize-1)/2].y/(rho),
|
|
|
|
1/(rho)));
|
|
|
|
1/(rho)));
|
|
|
|
dGpj_XpAj.block<3, 3>(0, 3) = Matrix<double, 3, 3>::Identity();
|
|
|
|
dGpj_XpAj.block<3, 3>(0, 3) = Matrix<double, 3, 3>::Identity();
|
|
|
|
|
|
|
|
|
|
|
@ -1750,41 +1771,61 @@ bool MsckfVio::PhotometricPatchPointJacobian(
|
|
|
|
bool MsckfVio::PhotometricMeasurementJacobian(
|
|
|
|
bool MsckfVio::PhotometricMeasurementJacobian(
|
|
|
|
const StateIDType& cam_state_id,
|
|
|
|
const StateIDType& cam_state_id,
|
|
|
|
const FeatureIDType& feature_id,
|
|
|
|
const FeatureIDType& feature_id,
|
|
|
|
MatrixXd& H_x, MatrixXd& H_y, VectorXd& r)
|
|
|
|
MatrixXd& H_x, MatrixXd& H_y, VectorXd& r, int patchsize)
|
|
|
|
{
|
|
|
|
{
|
|
|
|
// Prepare all the required data.
|
|
|
|
// Prepare all the required data.
|
|
|
|
const CAMState& cam_state = state_server.cam_states[cam_state_id];
|
|
|
|
const CAMState& cam_state = state_server.cam_states[cam_state_id];
|
|
|
|
const Feature& feature = map_server[feature_id];
|
|
|
|
const Feature& feature = map_server[feature_id];
|
|
|
|
|
|
|
|
|
|
|
|
//photometric observation
|
|
|
|
//photometric observation
|
|
|
|
VectorXd r_photo;
|
|
|
|
VectorXd r_photo = VectorXd::Zero(2*patchsize*patchsize);
|
|
|
|
|
|
|
|
|
|
|
|
// one line of the NxN Jacobians
|
|
|
|
// one line of the patchsizexpatchsize Jacobians
|
|
|
|
Eigen::Matrix<double, 2, 1> H_rhoj;
|
|
|
|
Eigen::Matrix<double, 2, 1> H_rhoj;
|
|
|
|
Eigen::Matrix<double, 2, 6> H_plj;
|
|
|
|
Eigen::Matrix<double, 2, 6> H_plj;
|
|
|
|
Eigen::Matrix<double, 2, 6> H_pAj;
|
|
|
|
Eigen::Matrix<double, 2, 6> H_pAj;
|
|
|
|
|
|
|
|
|
|
|
|
Eigen::MatrixXd dI_dh(2* N*N, 4);
|
|
|
|
Eigen::MatrixXd dI_dh(2* patchsize*patchsize, 4);
|
|
|
|
|
|
|
|
|
|
|
|
// combined Jacobians
|
|
|
|
// combined Jacobians
|
|
|
|
Eigen::MatrixXd H_rho(2 * N*N, 1);
|
|
|
|
Eigen::MatrixXd H_rho(2 * patchsize*patchsize, 1);
|
|
|
|
Eigen::MatrixXd H_pl(2 * N*N, 6);
|
|
|
|
Eigen::MatrixXd H_pl(2 * patchsize*patchsize, 6);
|
|
|
|
Eigen::MatrixXd H_pA(2 * N*N, 6);
|
|
|
|
Eigen::MatrixXd H_pA(2 * patchsize*patchsize, 6);
|
|
|
|
|
|
|
|
|
|
|
|
// calcualte residual of patch
|
|
|
|
// calcualte residual of patch
|
|
|
|
if (not PhotometricPatchPointResidual(cam_state_id, feature, r_photo))
|
|
|
|
if (not PhotometricPatchPointResidual(cam_state_id, feature, r_photo, patchsize))
|
|
|
|
|
|
|
|
{
|
|
|
|
return false;
|
|
|
|
return false;
|
|
|
|
|
|
|
|
}
|
|
|
|
//cout << "r\n" << r_photo << endl;
|
|
|
|
//cout << "r\n" << r_photo << endl;
|
|
|
|
// calculate jacobian for patch
|
|
|
|
// calculate jacobian for patch
|
|
|
|
int count = 0;
|
|
|
|
int count = 0;
|
|
|
|
bool valid = false;
|
|
|
|
bool valid = false;
|
|
|
|
Matrix<double, 2, 4> dI_dhj;// = Matrix<double, 1, 2>::Zero();
|
|
|
|
Matrix<double, 2, 4> dI_dhj;// = Matrix<double, 1, 2>::Zero();
|
|
|
|
int valid_count = 0;
|
|
|
|
int valid_count = 0;
|
|
|
|
for (auto point : feature.anchorPatch_3d)
|
|
|
|
|
|
|
|
|
|
|
|
std::vector<Eigen::Vector3d> new_anchorPatch_3d;
|
|
|
|
|
|
|
|
if (patchsize == 3 and N == 5)
|
|
|
|
|
|
|
|
{
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[6]);
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[7]);
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[8]);
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[11]);
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[12]);
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[13]);
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[16]);
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[17]);
|
|
|
|
|
|
|
|
new_anchorPatch_3d.push_back(feature.anchorPatch_3d[18]);
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
else
|
|
|
|
|
|
|
|
{
|
|
|
|
|
|
|
|
new_anchorPatch_3d = feature.anchorPatch_3d;
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
for(auto point : new_anchorPatch_3d)
|
|
|
|
{
|
|
|
|
{
|
|
|
|
// get jacobi of single point in patch
|
|
|
|
// get jacobi of single point in patch
|
|
|
|
if (PhotometricPatchPointJacobian(cam_state, cam_state_id, feature, point, count, H_rhoj, H_plj, H_pAj, dI_dhj))
|
|
|
|
if (PhotometricPatchPointJacobian(cam_state, cam_state_id, feature, point, count, patchsize, H_rhoj, H_plj, H_pAj, dI_dhj))
|
|
|
|
{
|
|
|
|
{
|
|
|
|
valid_count++;
|
|
|
|
valid_count++;
|
|
|
|
valid = true;
|
|
|
|
valid = true;
|
|
|
@ -1796,7 +1837,6 @@ bool MsckfVio::PhotometricMeasurementJacobian(
|
|
|
|
H_pA.block<2, 6>(count*2, 0) = H_pAj;
|
|
|
|
H_pA.block<2, 6>(count*2, 0) = H_pAj;
|
|
|
|
|
|
|
|
|
|
|
|
dI_dh.block<2, 4>(count*2, 0) = dI_dhj;
|
|
|
|
dI_dh.block<2, 4>(count*2, 0) = dI_dhj;
|
|
|
|
|
|
|
|
|
|
|
|
count++;
|
|
|
|
count++;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
// cout << "valid: " << valid_count << "/" << feature.anchorPatch_3d.size() << endl;
|
|
|
|
// cout << "valid: " << valid_count << "/" << feature.anchorPatch_3d.size() << endl;
|
|
|
@ -1807,7 +1847,7 @@ bool MsckfVio::PhotometricMeasurementJacobian(
|
|
|
|
MatrixXd H_xl;
|
|
|
|
MatrixXd H_xl;
|
|
|
|
MatrixXd H_yl;
|
|
|
|
MatrixXd H_yl;
|
|
|
|
|
|
|
|
|
|
|
|
ConstructJacobians(H_rho, H_pl, H_pA, feature, cam_state_id, H_xl, H_yl);
|
|
|
|
ConstructJacobians(H_rho, H_pl, H_pA, feature, cam_state_id, H_xl, H_yl, patchsize);
|
|
|
|
|
|
|
|
|
|
|
|
// set to return values
|
|
|
|
// set to return values
|
|
|
|
H_x = H_xl;
|
|
|
|
H_x = H_xl;
|
|
|
@ -1829,6 +1869,7 @@ bool MsckfVio::PhotometricMeasurementJacobian(
|
|
|
|
// visualizing functions
|
|
|
|
// visualizing functions
|
|
|
|
feature.MarkerGeneration(marker_pub, state_server.cam_states);
|
|
|
|
feature.MarkerGeneration(marker_pub, state_server.cam_states);
|
|
|
|
feature.VisualizePatch(cam_state, cam_state_id, cam0, r_photo, ss);
|
|
|
|
feature.VisualizePatch(cam_state, cam_state_id, cam0, r_photo, ss);
|
|
|
|
|
|
|
|
cout << "r\n" << r_photo << endl;
|
|
|
|
//feature.VisualizeKernel(cam_state, cam_state_id, cam0);
|
|
|
|
//feature.VisualizeKernel(cam_state, cam_state_id, cam0);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
@ -1845,16 +1886,17 @@ bool MsckfVio::ConstructJacobians(Eigen::MatrixXd& H_rho,
|
|
|
|
const Feature& feature,
|
|
|
|
const Feature& feature,
|
|
|
|
const StateIDType& cam_state_id,
|
|
|
|
const StateIDType& cam_state_id,
|
|
|
|
Eigen::MatrixXd& H_xl,
|
|
|
|
Eigen::MatrixXd& H_xl,
|
|
|
|
Eigen::MatrixXd& H_yl)
|
|
|
|
Eigen::MatrixXd& H_yl,
|
|
|
|
|
|
|
|
int patchsize)
|
|
|
|
{
|
|
|
|
{
|
|
|
|
H_xl = MatrixXd::Zero(2*N*N, 21+state_server.cam_states.size()*7);
|
|
|
|
H_xl = MatrixXd::Zero(2*patchsize*patchsize, 21+state_server.cam_states.size()*7);
|
|
|
|
H_yl = MatrixXd::Zero(2*N*N, 1);
|
|
|
|
H_yl = MatrixXd::Zero(2*patchsize*patchsize, 1);
|
|
|
|
|
|
|
|
|
|
|
|
// get position of anchor in cam states
|
|
|
|
// get position of anchor in cam states
|
|
|
|
auto cam_state_anchor = state_server.cam_states.find(feature.observations.begin()->first);
|
|
|
|
auto cam_state_anchor = state_server.cam_states.find(feature.observations.begin()->first);
|
|
|
|
int cam_state_cntr_anchor = std::distance(state_server.cam_states.begin(), cam_state_anchor);
|
|
|
|
int cam_state_cntr_anchor = std::distance(state_server.cam_states.begin(), cam_state_anchor);
|
|
|
|
// set anchor Jakobi
|
|
|
|
// set anchor Jakobi
|
|
|
|
H_xl.block(0, 21+cam_state_cntr_anchor*7, 2*N*N, 6) = H_pA;
|
|
|
|
H_xl.block(0, 21+cam_state_cntr_anchor*7, 2*patchsize*patchsize, 6) = H_pA;
|
|
|
|
|
|
|
|
|
|
|
|
//get position of current frame in cam states
|
|
|
|
//get position of current frame in cam states
|
|
|
|
auto cam_state_iter = state_server.cam_states.find(cam_state_id);
|
|
|
|
auto cam_state_iter = state_server.cam_states.find(cam_state_id);
|
|
|
@ -1862,7 +1904,7 @@ bool MsckfVio::ConstructJacobians(Eigen::MatrixXd& H_rho,
|
|
|
|
int cam_state_cntr = std::distance(state_server.cam_states.begin(), cam_state_iter);
|
|
|
|
int cam_state_cntr = std::distance(state_server.cam_states.begin(), cam_state_iter);
|
|
|
|
|
|
|
|
|
|
|
|
// set jakobi of state
|
|
|
|
// set jakobi of state
|
|
|
|
H_xl.block(0, 21+cam_state_cntr*7, 2*N*N, 6) = H_pl;
|
|
|
|
H_xl.block(0, 21+cam_state_cntr*7, 2*patchsize*patchsize, 6) = H_pl;
|
|
|
|
|
|
|
|
|
|
|
|
// set ones for irradiance bias
|
|
|
|
// set ones for irradiance bias
|
|
|
|
// H_xl.block(0, 21+cam_state_cntr*7+6, N*N, 1) = Eigen::ArrayXd::Ones(N*N);
|
|
|
|
// H_xl.block(0, 21+cam_state_cntr*7+6, N*N, 1) = Eigen::ArrayXd::Ones(N*N);
|
|
|
@ -1882,7 +1924,8 @@ bool MsckfVio::ConstructJacobians(Eigen::MatrixXd& H_rho,
|
|
|
|
bool MsckfVio::PhotometricFeatureJacobian(
|
|
|
|
bool MsckfVio::PhotometricFeatureJacobian(
|
|
|
|
const FeatureIDType& feature_id,
|
|
|
|
const FeatureIDType& feature_id,
|
|
|
|
const std::vector<StateIDType>& cam_state_ids,
|
|
|
|
const std::vector<StateIDType>& cam_state_ids,
|
|
|
|
MatrixXd& H_x, VectorXd& r)
|
|
|
|
MatrixXd& H_x, VectorXd& r,
|
|
|
|
|
|
|
|
int patchsize)
|
|
|
|
{
|
|
|
|
{
|
|
|
|
|
|
|
|
|
|
|
|
const auto& feature = map_server[feature_id];
|
|
|
|
const auto& feature = map_server[feature_id];
|
|
|
@ -1917,7 +1960,7 @@ bool MsckfVio::PhotometricFeatureJacobian(
|
|
|
|
for (const auto& cam_id : valid_cam_state_ids) {
|
|
|
|
for (const auto& cam_id : valid_cam_state_ids) {
|
|
|
|
|
|
|
|
|
|
|
|
// skip observation if measurement is not valid
|
|
|
|
// skip observation if measurement is not valid
|
|
|
|
if(not PhotometricMeasurementJacobian(cam_id, feature.id, H_xl, H_yl, r_l))
|
|
|
|
if(not PhotometricMeasurementJacobian(cam_id, feature.id, H_xl, H_yl, r_l, patchsize))
|
|
|
|
continue;
|
|
|
|
continue;
|
|
|
|
|
|
|
|
|
|
|
|
// set size of stacking jacobians, once the returned jacobians are known
|
|
|
|
// set size of stacking jacobians, once the returned jacobians are known
|
|
|
@ -2590,6 +2633,7 @@ bool MsckfVio::gatingTest(const MatrixXd& H, const VectorXd& r, const int& dof,
|
|
|
|
|
|
|
|
|
|
|
|
double gamma = r.transpose() * (P1+P2).ldlt().solve(r);
|
|
|
|
double gamma = r.transpose() * (P1+P2).ldlt().solve(r);
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
if(gamma > 1000000)
|
|
|
|
if(gamma > 1000000)
|
|
|
|
{
|
|
|
|
{
|
|
|
|
cout << " logging " << endl;
|
|
|
|
cout << " logging " << endl;
|
|
|
@ -2615,14 +2659,17 @@ bool MsckfVio::gatingTest(const MatrixXd& H, const VectorXd& r, const int& dof,
|
|
|
|
<< state_server.state_cov << endl;
|
|
|
|
<< state_server.state_cov << endl;
|
|
|
|
myfile.close();
|
|
|
|
myfile.close();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
*/
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (chi_squared_test_table[dof] == 0)
|
|
|
|
if (chi_squared_test_table[dof] == 0)
|
|
|
|
return false;
|
|
|
|
return false;
|
|
|
|
if (gamma < chi_squared_test_table[dof]) {
|
|
|
|
if (gamma < chi_squared_test_table[dof]) {
|
|
|
|
// cout << "passed" << endl;
|
|
|
|
|
|
|
|
if(filter == 1)
|
|
|
|
if(filter == 1)
|
|
|
|
cout << "gate: " << dof << " " << gamma << " " <<
|
|
|
|
cout << "gate: " << dof << " " << gamma << " " <<
|
|
|
|
chi_squared_test_table[dof] << endl;
|
|
|
|
chi_squared_test_table[dof] << endl;
|
|
|
|
|
|
|
|
// cout << "passed" << endl;
|
|
|
|
return true;
|
|
|
|
return true;
|
|
|
|
} else {
|
|
|
|
} else {
|
|
|
|
// cout << "failed" << endl;
|
|
|
|
// cout << "failed" << endl;
|
|
|
@ -2635,6 +2682,7 @@ void MsckfVio::removeLostFeatures() {
|
|
|
|
// BTW, find the size the final Jacobian matrix and residual vector.
|
|
|
|
// BTW, find the size the final Jacobian matrix and residual vector.
|
|
|
|
int jacobian_row_size = 0;
|
|
|
|
int jacobian_row_size = 0;
|
|
|
|
int pjacobian_row_size = 0;
|
|
|
|
int pjacobian_row_size = 0;
|
|
|
|
|
|
|
|
int p2jacobian_row_size = 0;
|
|
|
|
int twojacobian_row_size = 0;
|
|
|
|
int twojacobian_row_size = 0;
|
|
|
|
|
|
|
|
|
|
|
|
vector<FeatureIDType> invalid_feature_ids(0);
|
|
|
|
vector<FeatureIDType> invalid_feature_ids(0);
|
|
|
@ -2676,6 +2724,7 @@ void MsckfVio::removeLostFeatures() {
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
pjacobian_row_size += 2*N*N*feature.observations.size();
|
|
|
|
pjacobian_row_size += 2*N*N*feature.observations.size();
|
|
|
|
|
|
|
|
p2jacobian_row_size += 2*3*3*feature.observations.size();
|
|
|
|
twojacobian_row_size += 4*feature.observations.size();
|
|
|
|
twojacobian_row_size += 4*feature.observations.size();
|
|
|
|
jacobian_row_size += 4*feature.observations.size() - 3;
|
|
|
|
jacobian_row_size += 4*feature.observations.size() - 3;
|
|
|
|
|
|
|
|
|
|
|
@ -2704,6 +2753,10 @@ void MsckfVio::removeLostFeatures() {
|
|
|
|
VectorXd pr = VectorXd::Zero(pjacobian_row_size);
|
|
|
|
VectorXd pr = VectorXd::Zero(pjacobian_row_size);
|
|
|
|
int pstack_cntr = 0;
|
|
|
|
int pstack_cntr = 0;
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
MatrixXd p2H_x = MatrixXd::Zero(p2jacobian_row_size,
|
|
|
|
|
|
|
|
21+7*state_server.cam_states.size());
|
|
|
|
|
|
|
|
VectorXd p2r = VectorXd::Zero(p2jacobian_row_size);
|
|
|
|
|
|
|
|
int p2stack_cntr = 0;
|
|
|
|
|
|
|
|
|
|
|
|
MatrixXd twoH_x = MatrixXd::Zero(twojacobian_row_size,
|
|
|
|
MatrixXd twoH_x = MatrixXd::Zero(twojacobian_row_size,
|
|
|
|
21+7*state_server.cam_states.size());
|
|
|
|
21+7*state_server.cam_states.size());
|
|
|
@ -2720,12 +2773,17 @@ void MsckfVio::removeLostFeatures() {
|
|
|
|
|
|
|
|
|
|
|
|
MatrixXd H_xj;
|
|
|
|
MatrixXd H_xj;
|
|
|
|
VectorXd r_j;
|
|
|
|
VectorXd r_j;
|
|
|
|
MatrixXd pH_xj;
|
|
|
|
|
|
|
|
VectorXd pr_j;
|
|
|
|
|
|
|
|
MatrixXd twoH_xj;
|
|
|
|
MatrixXd twoH_xj;
|
|
|
|
VectorXd twor_j;
|
|
|
|
VectorXd twor_j;
|
|
|
|
|
|
|
|
|
|
|
|
if(PhotometricFeatureJacobian(feature.id, cam_state_ids, pH_xj, pr_j))
|
|
|
|
MatrixXd pH_xj;
|
|
|
|
|
|
|
|
VectorXd pr_j;
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
MatrixXd p2H_xj;
|
|
|
|
|
|
|
|
VectorXd p2r_j;
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if(PhotometricFeatureJacobian(feature.id, cam_state_ids, pH_xj, pr_j, N))
|
|
|
|
{
|
|
|
|
{
|
|
|
|
if (gatingTest(pH_xj, pr_j, pr_j.size(), 1)) { //, cam_state_ids.size()-1)) {
|
|
|
|
if (gatingTest(pH_xj, pr_j, pr_j.size(), 1)) { //, cam_state_ids.size()-1)) {
|
|
|
|
pH_x.block(pstack_cntr, 0, pH_xj.rows(), pH_xj.cols()) = pH_xj;
|
|
|
|
pH_x.block(pstack_cntr, 0, pH_xj.rows(), pH_xj.cols()) = pH_xj;
|
|
|
@ -2734,6 +2792,18 @@ void MsckfVio::removeLostFeatures() {
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
|
|
|
cout << "3: " << endl;
|
|
|
|
|
|
|
|
if(PhotometricFeatureJacobian(feature.id, cam_state_ids, p2H_xj, p2r_j, 3))
|
|
|
|
|
|
|
|
{
|
|
|
|
|
|
|
|
if (gatingTest(p2H_xj, p2r_j, p2r_j.size(), 1)) { //, cam_state_ids.size()-1)) {
|
|
|
|
|
|
|
|
cout << p2H_x.rows() << ":" << p2H_x.cols() << ", " << p2H_xj.rows() << ":" << p2H_xj.cols() << endl;
|
|
|
|
|
|
|
|
p2H_x.block(p2stack_cntr, 0, p2H_xj.rows(), p2H_xj.cols()) = p2H_xj;
|
|
|
|
|
|
|
|
p2r.segment(p2stack_cntr, p2r_j.rows()) = p2r_j;
|
|
|
|
|
|
|
|
p2stack_cntr += p2H_xj.rows();
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
*/
|
|
|
|
featureJacobian(feature.id, cam_state_ids, H_xj, r_j);
|
|
|
|
featureJacobian(feature.id, cam_state_ids, H_xj, r_j);
|
|
|
|
twodotFeatureJacobian(feature.id, cam_state_ids, twoH_xj, twor_j);
|
|
|
|
twodotFeatureJacobian(feature.id, cam_state_ids, twoH_xj, twor_j);
|
|
|
|
|
|
|
|
|
|
|
@ -2831,6 +2901,7 @@ void MsckfVio::pruneLastCamStateBuffer()
|
|
|
|
// Set the size of the Jacobian matrix.
|
|
|
|
// Set the size of the Jacobian matrix.
|
|
|
|
int jacobian_row_size = 0;
|
|
|
|
int jacobian_row_size = 0;
|
|
|
|
int pjacobian_row_size = 0;
|
|
|
|
int pjacobian_row_size = 0;
|
|
|
|
|
|
|
|
int p2jacobian_row_size = 0;
|
|
|
|
int twojacobian_row_size = 0;
|
|
|
|
int twojacobian_row_size = 0;
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
@ -2869,6 +2940,7 @@ void MsckfVio::pruneLastCamStateBuffer()
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
pjacobian_row_size += 2*N*N*feature.observations.size();
|
|
|
|
pjacobian_row_size += 2*N*N*feature.observations.size();
|
|
|
|
|
|
|
|
p2jacobian_row_size += 2*3*3*feature.observations.size();
|
|
|
|
jacobian_row_size += 4*feature.observations.size() - 3;
|
|
|
|
jacobian_row_size += 4*feature.observations.size() - 3;
|
|
|
|
twojacobian_row_size += 4*feature.observations.size();
|
|
|
|
twojacobian_row_size += 4*feature.observations.size();
|
|
|
|
|
|
|
|
|
|
|
@ -2884,11 +2956,16 @@ void MsckfVio::pruneLastCamStateBuffer()
|
|
|
|
VectorXd pr = VectorXd::Zero(pjacobian_row_size);
|
|
|
|
VectorXd pr = VectorXd::Zero(pjacobian_row_size);
|
|
|
|
MatrixXd twoH_xj;
|
|
|
|
MatrixXd twoH_xj;
|
|
|
|
VectorXd twor_j;
|
|
|
|
VectorXd twor_j;
|
|
|
|
|
|
|
|
MatrixXd p2H_x = MatrixXd::Zero(p2jacobian_row_size, 21+7*state_server.cam_states.size());
|
|
|
|
|
|
|
|
VectorXd p2r = VectorXd::Zero(p2jacobian_row_size);
|
|
|
|
|
|
|
|
MatrixXd p2H_xj;
|
|
|
|
|
|
|
|
VectorXd p2r_j;
|
|
|
|
MatrixXd twoH_x = MatrixXd::Zero(twojacobian_row_size, 21+7*state_server.cam_states.size());
|
|
|
|
MatrixXd twoH_x = MatrixXd::Zero(twojacobian_row_size, 21+7*state_server.cam_states.size());
|
|
|
|
VectorXd twor = VectorXd::Zero(twojacobian_row_size);
|
|
|
|
VectorXd twor = VectorXd::Zero(twojacobian_row_size);
|
|
|
|
int stack_cntr = 0;
|
|
|
|
int stack_cntr = 0;
|
|
|
|
int pruned_cntr = 0;
|
|
|
|
int pruned_cntr = 0;
|
|
|
|
int pstack_cntr = 0;
|
|
|
|
int pstack_cntr = 0;
|
|
|
|
|
|
|
|
int p2stack_cntr = 0;
|
|
|
|
int twostack_cntr = 0;
|
|
|
|
int twostack_cntr = 0;
|
|
|
|
|
|
|
|
|
|
|
|
for (auto& item : map_server) {
|
|
|
|
for (auto& item : map_server) {
|
|
|
@ -2904,10 +2981,8 @@ void MsckfVio::pruneLastCamStateBuffer()
|
|
|
|
for (const auto& cam_state : state_server.cam_states)
|
|
|
|
for (const auto& cam_state : state_server.cam_states)
|
|
|
|
involved_cam_state_ids.push_back(cam_state.first);
|
|
|
|
involved_cam_state_ids.push_back(cam_state.first);
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if(PhotometricFeatureJacobian(feature.id, involved_cam_state_ids, pH_xj, pr_j, N))
|
|
|
|
if(PhotometricFeatureJacobian(feature.id, involved_cam_state_ids, pH_xj, pr_j) == true)
|
|
|
|
|
|
|
|
{
|
|
|
|
{
|
|
|
|
|
|
|
|
|
|
|
|
if (gatingTest(pH_xj, pr_j, pr_j.size(), 1)) { //, cam_state_ids.size()-1)) {
|
|
|
|
if (gatingTest(pH_xj, pr_j, pr_j.size(), 1)) { //, cam_state_ids.size()-1)) {
|
|
|
|
pH_x.block(pstack_cntr, 0, pH_xj.rows(), pH_xj.cols()) = pH_xj;
|
|
|
|
pH_x.block(pstack_cntr, 0, pH_xj.rows(), pH_xj.cols()) = pH_xj;
|
|
|
|
pr.segment(pstack_cntr, pr_j.rows()) = pr_j;
|
|
|
|
pr.segment(pstack_cntr, pr_j.rows()) = pr_j;
|
|
|
@ -2915,6 +2990,17 @@ void MsckfVio::pruneLastCamStateBuffer()
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
|
|
|
cout << "3: " << endl;
|
|
|
|
|
|
|
|
if(PhotometricFeatureJacobian(feature.id, involved_cam_state_ids, p2H_xj, p2r_j, 3))
|
|
|
|
|
|
|
|
{
|
|
|
|
|
|
|
|
if (gatingTest(p2H_xj, p2r_j, p2r_j.size(), 1)) { //, cam_state_ids.size()-1)) {
|
|
|
|
|
|
|
|
p2H_x.block(p2stack_cntr, 0, p2H_xj.rows(), p2H_xj.cols()) = p2H_xj;
|
|
|
|
|
|
|
|
p2r.segment(p2stack_cntr, p2r_j.rows()) = p2r_j;
|
|
|
|
|
|
|
|
p2stack_cntr += p2H_xj.rows();
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
*/
|
|
|
|
featureJacobian(feature.id, involved_cam_state_ids, H_xj, r_j);
|
|
|
|
featureJacobian(feature.id, involved_cam_state_ids, H_xj, r_j);
|
|
|
|
twodotFeatureJacobian(feature.id, involved_cam_state_ids, twoH_xj, twor_j);
|
|
|
|
twodotFeatureJacobian(feature.id, involved_cam_state_ids, twoH_xj, twor_j);
|
|
|
|
|
|
|
|
|
|
|
@ -3003,6 +3089,7 @@ void MsckfVio::pruneCamStateBuffer() {
|
|
|
|
// Find the size of the Jacobian matrix.
|
|
|
|
// Find the size of the Jacobian matrix.
|
|
|
|
int jacobian_row_size = 0;
|
|
|
|
int jacobian_row_size = 0;
|
|
|
|
int pjacobian_row_size = 0;
|
|
|
|
int pjacobian_row_size = 0;
|
|
|
|
|
|
|
|
int p2jacobian_row_size = 0;
|
|
|
|
int twojacobian_row_size = 0;
|
|
|
|
int twojacobian_row_size = 0;
|
|
|
|
|
|
|
|
|
|
|
|
for (auto& item : map_server) {
|
|
|
|
for (auto& item : map_server) {
|
|
|
@ -3050,6 +3137,7 @@ void MsckfVio::pruneCamStateBuffer() {
|
|
|
|
|
|
|
|
|
|
|
|
twojacobian_row_size += 4*involved_cam_state_ids.size();
|
|
|
|
twojacobian_row_size += 4*involved_cam_state_ids.size();
|
|
|
|
pjacobian_row_size += 2*N*N*involved_cam_state_ids.size();
|
|
|
|
pjacobian_row_size += 2*N*N*involved_cam_state_ids.size();
|
|
|
|
|
|
|
|
p2jacobian_row_size += 2*3*3*involved_cam_state_ids.size();
|
|
|
|
jacobian_row_size += 4*involved_cam_state_ids.size() - 3;
|
|
|
|
jacobian_row_size += 4*involved_cam_state_ids.size() - 3;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
@ -3061,11 +3149,19 @@ void MsckfVio::pruneCamStateBuffer() {
|
|
|
|
MatrixXd H_x = MatrixXd::Zero(jacobian_row_size, 21+7*state_server.cam_states.size());
|
|
|
|
MatrixXd H_x = MatrixXd::Zero(jacobian_row_size, 21+7*state_server.cam_states.size());
|
|
|
|
VectorXd r = VectorXd::Zero(jacobian_row_size);
|
|
|
|
VectorXd r = VectorXd::Zero(jacobian_row_size);
|
|
|
|
int stack_cntr = 0;
|
|
|
|
int stack_cntr = 0;
|
|
|
|
|
|
|
|
|
|
|
|
MatrixXd pH_xj;
|
|
|
|
MatrixXd pH_xj;
|
|
|
|
VectorXd pr_j;
|
|
|
|
VectorXd pr_j;
|
|
|
|
MatrixXd pH_x = MatrixXd::Zero(pjacobian_row_size, 21+7*state_server.cam_states.size());
|
|
|
|
MatrixXd pH_x = MatrixXd::Zero(pjacobian_row_size, 21+7*state_server.cam_states.size());
|
|
|
|
VectorXd pr = VectorXd::Zero(pjacobian_row_size);
|
|
|
|
VectorXd pr = VectorXd::Zero(pjacobian_row_size);
|
|
|
|
int pstack_cntr = 0;
|
|
|
|
int pstack_cntr = 0;
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
MatrixXd p2H_x = MatrixXd::Zero(p2jacobian_row_size, 21+7*state_server.cam_states.size());
|
|
|
|
|
|
|
|
VectorXd p2r = VectorXd::Zero(p2jacobian_row_size);
|
|
|
|
|
|
|
|
MatrixXd p2H_xj;
|
|
|
|
|
|
|
|
VectorXd p2r_j;
|
|
|
|
|
|
|
|
int p2stack_cntr = 0;
|
|
|
|
|
|
|
|
|
|
|
|
MatrixXd twoH_xj;
|
|
|
|
MatrixXd twoH_xj;
|
|
|
|
VectorXd twor_j;
|
|
|
|
VectorXd twor_j;
|
|
|
|
MatrixXd twoH_x = MatrixXd::Zero(twojacobian_row_size, 21+7*state_server.cam_states.size());
|
|
|
|
MatrixXd twoH_x = MatrixXd::Zero(twojacobian_row_size, 21+7*state_server.cam_states.size());
|
|
|
@ -3084,14 +3180,27 @@ void MsckfVio::pruneCamStateBuffer() {
|
|
|
|
|
|
|
|
|
|
|
|
if (involved_cam_state_ids.size() == 0) continue;
|
|
|
|
if (involved_cam_state_ids.size() == 0) continue;
|
|
|
|
|
|
|
|
|
|
|
|
if(PhotometricFeatureJacobian(feature.id, involved_cam_state_ids, pH_xj, pr_j) == true)
|
|
|
|
if(PhotometricFeatureJacobian(feature.id, involved_cam_state_ids, pH_xj, pr_j, N))
|
|
|
|
{
|
|
|
|
{
|
|
|
|
if (gatingTest(pH_xj, pr_j, pr_j.size(), 1)) {// involved_cam_state_ids.size())) {
|
|
|
|
if (gatingTest(pH_xj, pr_j, pr_j.size(), 1)) {// involved_cam_state_ids.size())) {
|
|
|
|
pH_x.block(pstack_cntr, 0, pH_xj.rows(), pH_xj.cols()) = pH_xj;
|
|
|
|
pH_x.block(pstack_cntr, 0, pH_xj.rows(), pH_xj.cols()) = pH_xj;
|
|
|
|
pr.segment(pstack_cntr, pr_j.rows()) = pr_j;
|
|
|
|
pr.segment(pstack_cntr, pr_j.rows()) = pr_j;
|
|
|
|
pstack_cntr += pH_xj.rows();
|
|
|
|
pstack_cntr += pH_xj.rows();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
|
|
|
cout << "3: " << endl;
|
|
|
|
|
|
|
|
if(PhotometricFeatureJacobian(feature.id, involved_cam_state_ids, p2H_xj, p2r_j, 3))
|
|
|
|
|
|
|
|
{
|
|
|
|
|
|
|
|
if (gatingTest(p2H_xj, p2r_j, p2r_j.size(), 1)) { //, cam_state_ids.size()-1)) {
|
|
|
|
|
|
|
|
p2H_x.block(p2stack_cntr, 0, p2H_xj.rows(), p2H_xj.cols()) = p2H_xj;
|
|
|
|
|
|
|
|
p2r.segment(p2stack_cntr, p2r_j.rows()) = p2r_j;
|
|
|
|
|
|
|
|
p2stack_cntr += p2H_xj.rows();
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
*/
|
|
|
|
|
|
|
|
|
|
|
|
featureJacobian(feature.id, involved_cam_state_ids, H_xj, r_j);
|
|
|
|
featureJacobian(feature.id, involved_cam_state_ids, H_xj, r_j);
|
|
|
|
twodotFeatureJacobian(feature.id, involved_cam_state_ids, twoH_xj, twor_j);
|
|
|
|
twodotFeatureJacobian(feature.id, involved_cam_state_ids, twoH_xj, twor_j);
|
|
|
|
|
|
|
|
|
|
|
|