00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include "rtabmap/core/OdometryMSCKF.h"
00029 #include "rtabmap/core/OdometryInfo.h"
00030 #include "rtabmap/core/util3d_transforms.h"
00031 #include "rtabmap/utilite/ULogger.h"
00032 #include "rtabmap/utilite/UTimer.h"
00033 #include "rtabmap/utilite/UStl.h"
00034 #include "rtabmap/utilite/UThread.h"
00035
00036 #ifdef RTABMAP_MSCKF_VIO
00037 #include <msckf_vio/image_processor.h>
00038 #include <msckf_vio/msckf_vio.h>
00039 #include <msckf_vio/math_utils.hpp>
00040 #include <eigen_conversions/eigen_msg.h>
00041 #include <boost/math/distributions/chi_squared.hpp>
00042 #include <pcl/common/transforms.h>
00043 #endif
00044
00045 namespace rtabmap {
00046
00047 #ifdef RTABMAP_MSCKF_VIO
00048 class ImageProcessorNoROS: public msckf_vio::ImageProcessor
00049 {
00050 public:
00051 ImageProcessorNoROS(
00052 const ParametersMap & parameters_in,
00053 const Transform & imuLocalTransform,
00054 const StereoCameraModel & model,
00055 bool rectified) :
00056 msckf_vio::ImageProcessor(0)
00057 {
00058 UDEBUG("");
00059
00060 if(model.left().D_raw().cols == 6)
00061 {
00062
00063 cam0_distortion_model = "equidistant";
00064 cam0_distortion_coeffs[0] = rectified?0:model.left().D_raw().at<double>(0,0);
00065 cam0_distortion_coeffs[1] = rectified?0:model.left().D_raw().at<double>(0,1);
00066 cam0_distortion_coeffs[2] = rectified?0:model.left().D_raw().at<double>(0,4);
00067 cam0_distortion_coeffs[3] = rectified?0:model.left().D_raw().at<double>(0,5);
00068 }
00069 else
00070 {
00071
00072 cam0_distortion_model = "radtan";
00073 cam0_distortion_coeffs[0] = rectified?0:model.left().D_raw().at<double>(0,0);
00074 cam0_distortion_coeffs[1] = rectified?0:model.left().D_raw().at<double>(0,1);
00075 cam0_distortion_coeffs[2] = rectified?0:model.left().D_raw().at<double>(0,2);
00076 cam0_distortion_coeffs[3] = rectified?0:model.left().D_raw().at<double>(0,3);
00077 }
00078 if(model.right().D_raw().cols == 6)
00079 {
00080
00081 cam1_distortion_model = "equidistant";
00082 cam1_distortion_coeffs[0] = rectified?0:model.right().D_raw().at<double>(0,0);
00083 cam1_distortion_coeffs[1] = rectified?0:model.right().D_raw().at<double>(0,1);
00084 cam1_distortion_coeffs[2] = rectified?0:model.right().D_raw().at<double>(0,4);
00085 cam1_distortion_coeffs[3] = rectified?0:model.right().D_raw().at<double>(0,5);
00086 }
00087 else
00088 {
00089
00090 cam1_distortion_model = "radtan";
00091 cam1_distortion_coeffs[0] = rectified?0:model.right().D_raw().at<double>(0,0);
00092 cam1_distortion_coeffs[1] = rectified?0:model.right().D_raw().at<double>(0,1);
00093 cam1_distortion_coeffs[2] = rectified?0:model.right().D_raw().at<double>(0,2);
00094 cam1_distortion_coeffs[3] = rectified?0:model.right().D_raw().at<double>(0,3);
00095 }
00096
00097 cam0_resolution[0] = model.left().imageWidth();
00098 cam0_resolution[1] = model.left().imageHeight();
00099
00100 cam1_resolution[0] = model.right().imageWidth();
00101 cam1_resolution[1] = model.right().imageHeight();
00102
00103 cam0_intrinsics[0] = rectified?model.left().fx():model.left().K_raw().at<double>(0,0);
00104 cam0_intrinsics[1] = rectified?model.left().fy():model.left().K_raw().at<double>(1,1);
00105 cam0_intrinsics[2] = rectified?model.left().cx():model.left().K_raw().at<double>(0,2);
00106 cam0_intrinsics[3] = rectified?model.left().cy():model.left().K_raw().at<double>(1,2);
00107
00108 cam1_intrinsics[0] = rectified?model.right().fx():model.right().K_raw().at<double>(0,0);
00109 cam1_intrinsics[1] = rectified?model.right().fy():model.right().K_raw().at<double>(1,1);
00110 cam1_intrinsics[2] = rectified?model.right().cx():model.right().K_raw().at<double>(0,2);
00111 cam1_intrinsics[3] = rectified?model.right().cy():model.right().K_raw().at<double>(1,2);
00112
00113 Transform imuCam = model.localTransform().inverse() * imuLocalTransform;
00114 cv::Mat T_imu_cam0 = imuCam.dataMatrix();
00115 cv::Matx33d R_imu_cam0(T_imu_cam0(cv::Rect(0,0,3,3)));
00116 cv::Vec3d t_imu_cam0 = T_imu_cam0(cv::Rect(3,0,1,3));
00117 R_cam0_imu = R_imu_cam0.t();
00118 t_cam0_imu = -R_imu_cam0.t() * t_imu_cam0;
00119
00120 Transform cam0cam1;
00121 if(rectified)
00122 {
00123 cam0cam1 = Transform(
00124 1, 0, 0, -model.baseline(),
00125 0, 1, 0, 0,
00126 0, 0, 1, 0);
00127 }
00128 else
00129 {
00130 cam0cam1 = model.stereoTransform();
00131 }
00132
00133 UASSERT(!cam0cam1.isNull());
00134 Transform imuCam1 = cam0cam1 * imuCam;
00135 cv::Mat T_imu_cam1 = imuCam1.dataMatrix();
00136 cv::Matx33d R_imu_cam1(T_imu_cam1(cv::Rect(0,0,3,3)));
00137 cv::Vec3d t_imu_cam1 = T_imu_cam1(cv::Rect(3,0,1,3));
00138 R_cam1_imu = R_imu_cam1.t();
00139 t_cam1_imu = -R_imu_cam1.t() * t_imu_cam1;
00140
00141
00142 ParametersMap parameters = Parameters::getDefaultParameters("OdomMSCKF");
00143 uInsert(parameters, parameters_in);
00144
00145 Parameters::parse(parameters, Parameters::kOdomMSCKFGridRow(), processor_config.grid_row);
00146 Parameters::parse(parameters, Parameters::kOdomMSCKFGridCol(), processor_config.grid_col);
00147 Parameters::parse(parameters, Parameters::kOdomMSCKFGridMinFeatureNum(), processor_config.grid_min_feature_num);
00148 Parameters::parse(parameters, Parameters::kOdomMSCKFGridMaxFeatureNum(), processor_config.grid_max_feature_num);
00149 Parameters::parse(parameters, Parameters::kOdomMSCKFPyramidLevels(), processor_config.pyramid_levels);
00150 Parameters::parse(parameters, Parameters::kOdomMSCKFPatchSize(), processor_config.patch_size);
00151 Parameters::parse(parameters, Parameters::kOdomMSCKFFastThreshold(), processor_config.fast_threshold);
00152 Parameters::parse(parameters, Parameters::kOdomMSCKFMaxIteration(), processor_config.max_iteration);
00153 Parameters::parse(parameters, Parameters::kOdomMSCKFTrackPrecision(), processor_config.track_precision);
00154 Parameters::parse(parameters, Parameters::kOdomMSCKFRansacThreshold(), processor_config.ransac_threshold);
00155 Parameters::parse(parameters, Parameters::kOdomMSCKFStereoThreshold(), processor_config.stereo_threshold);
00156
00157 UINFO("===========================================");
00158 UINFO("cam0_resolution: %d, %d",
00159 cam0_resolution[0], cam0_resolution[1]);
00160 UINFO("cam0_intrinscs: %f, %f, %f, %f",
00161 cam0_intrinsics[0], cam0_intrinsics[1],
00162 cam0_intrinsics[2], cam0_intrinsics[3]);
00163 UINFO("cam0_distortion_model: %s",
00164 cam0_distortion_model.c_str());
00165 UINFO("cam0_distortion_coefficients: %f, %f, %f, %f",
00166 cam0_distortion_coeffs[0], cam0_distortion_coeffs[1],
00167 cam0_distortion_coeffs[2], cam0_distortion_coeffs[3]);
00168
00169 UINFO("cam1_resolution: %d, %d",
00170 cam1_resolution[0], cam1_resolution[1]);
00171 UINFO("cam1_intrinscs: %f, %f, %f, %f",
00172 cam1_intrinsics[0], cam1_intrinsics[1],
00173 cam1_intrinsics[2], cam1_intrinsics[3]);
00174 UINFO("cam1_distortion_model: %s",
00175 cam1_distortion_model.c_str());
00176 UINFO("cam1_distortion_coefficients: %f, %f, %f, %f",
00177 cam1_distortion_coeffs[0], cam1_distortion_coeffs[1],
00178 cam1_distortion_coeffs[2], cam1_distortion_coeffs[3]);
00179
00180 std::cout << "R_imu_cam0: " << R_imu_cam0 << std::endl;
00181 std::cout << "t_imu_cam0.t(): " << t_imu_cam0.t() << std::endl;
00182 std::cout << "R_imu_cam1: " << R_imu_cam1 << std::endl;
00183 std::cout << "t_imu_cam1.t(): " << t_imu_cam1.t() << std::endl;
00184
00185 UINFO("grid_row: %d",
00186 processor_config.grid_row);
00187 UINFO("grid_col: %d",
00188 processor_config.grid_col);
00189 UINFO("grid_min_feature_num: %d",
00190 processor_config.grid_min_feature_num);
00191 UINFO("grid_max_feature_num: %d",
00192 processor_config.grid_max_feature_num);
00193 UINFO("pyramid_levels: %d",
00194 processor_config.pyramid_levels);
00195 UINFO("patch_size: %d",
00196 processor_config.patch_size);
00197 UINFO("fast_threshold: %d",
00198 processor_config.fast_threshold);
00199 UINFO("max_iteration: %d",
00200 processor_config.max_iteration);
00201 UINFO("track_precision: %f",
00202 processor_config.track_precision);
00203 UINFO("ransac_threshold: %f",
00204 processor_config.ransac_threshold);
00205 UINFO("stereo_threshold: %f",
00206 processor_config.stereo_threshold);
00207 UINFO("===========================================");
00208
00209
00210 detector_ptr = cv::FastFeatureDetector::create(
00211 processor_config.fast_threshold);
00212 }
00213
00214 virtual ~ImageProcessorNoROS() {}
00215
00216 msckf_vio::CameraMeasurementPtr stereoCallback2(
00217 const sensor_msgs::ImageConstPtr& cam0_img,
00218 const sensor_msgs::ImageConstPtr& cam1_img) {
00219
00220
00221
00222
00223
00224 cam0_curr_img_ptr = cv_bridge::toCvShare(cam0_img,
00225 sensor_msgs::image_encodings::MONO8);
00226 cam1_curr_img_ptr = cv_bridge::toCvShare(cam1_img,
00227 sensor_msgs::image_encodings::MONO8);
00228
00229
00230 createImagePyramids();
00231
00232
00233 if (is_first_img) {
00234
00235 initializeFirstFrame();
00236
00237
00238 is_first_img = false;
00239
00240
00241
00242
00243
00244
00245 } else {
00246
00247
00248 trackFeatures();
00249
00250
00251
00252
00253
00254 addNewFeatures();
00255
00256
00257
00258
00259
00260 pruneGridFeatures();
00261
00262
00263
00264
00265
00266
00267
00268
00269 }
00270
00271
00272
00273
00274
00275
00276
00277
00278 msckf_vio::CameraMeasurementPtr measurements = publish();
00279
00280
00281
00282
00283 cam0_prev_img_ptr = cam0_curr_img_ptr;
00284 prev_features_ptr = curr_features_ptr;
00285 std::swap(prev_cam0_pyramid_, curr_cam0_pyramid_);
00286
00287
00288 curr_features_ptr.reset(new GridFeatures());
00289 for (int code = 0; code <
00290 processor_config.grid_row*processor_config.grid_col; ++code) {
00291 (*curr_features_ptr)[code] = std::vector<FeatureMetaData>(0);
00292 }
00293
00294 return measurements;
00295 }
00296
00297 msckf_vio::CameraMeasurementPtr publish() {
00298
00299
00300 msckf_vio::CameraMeasurementPtr feature_msg_ptr(new msckf_vio::CameraMeasurement);
00301 feature_msg_ptr->header.stamp = cam0_curr_img_ptr->header.stamp;
00302
00303 std::vector<FeatureIDType> curr_ids(0);
00304 std::vector<cv::Point2f> curr_cam0_points(0);
00305 std::vector<cv::Point2f> curr_cam1_points(0);
00306
00307 for (const auto& grid_features : (*curr_features_ptr)) {
00308 for (const auto& feature : grid_features.second) {
00309 curr_ids.push_back(feature.id);
00310 curr_cam0_points.push_back(feature.cam0_point);
00311 curr_cam1_points.push_back(feature.cam1_point);
00312 }
00313 }
00314
00315 std::vector<cv::Point2f> curr_cam0_points_undistorted(0);
00316 std::vector<cv::Point2f> curr_cam1_points_undistorted(0);
00317
00318 undistortPoints(
00319 curr_cam0_points, cam0_intrinsics, cam0_distortion_model,
00320 cam0_distortion_coeffs, curr_cam0_points_undistorted);
00321 undistortPoints(
00322 curr_cam1_points, cam1_intrinsics, cam1_distortion_model,
00323 cam1_distortion_coeffs, curr_cam1_points_undistorted);
00324
00325 for (unsigned int i = 0; i < curr_ids.size(); ++i) {
00326 feature_msg_ptr->features.push_back(msckf_vio::FeatureMeasurement());
00327 feature_msg_ptr->features[i].id = curr_ids[i];
00328 feature_msg_ptr->features[i].u0 = curr_cam0_points_undistorted[i].x;
00329 feature_msg_ptr->features[i].v0 = curr_cam0_points_undistorted[i].y;
00330 feature_msg_ptr->features[i].u1 = curr_cam1_points_undistorted[i].x;
00331 feature_msg_ptr->features[i].v1 = curr_cam1_points_undistorted[i].y;
00332 }
00333
00334
00335
00336
00337
00338
00339
00340
00341
00342
00343
00344
00345 return feature_msg_ptr;
00346 }
00347 };
00348
00349 class MsckfVioNoROS: public msckf_vio::MsckfVio
00350 {
00351 public:
00352 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00353
00354 MsckfVioNoROS(const ParametersMap & parameters_in,
00355 const Transform & imuLocalTransform,
00356 const StereoCameraModel & model,
00357 bool rectified) :
00358 msckf_vio::MsckfVio(0)
00359 {
00360 UDEBUG("");
00361
00362 parameters_ = Parameters::getDefaultParameters("OdomMSCKF");
00363 uInsert(parameters_, parameters_in);
00364
00365
00366 publish_tf = false;
00367 frame_rate = 1.0;
00368 Parameters::parse(parameters_, Parameters::kOdomMSCKFPositionStdThreshold(), position_std_threshold);
00369
00370 Parameters::parse(parameters_, Parameters::kOdomMSCKFRotationThreshold(), rotation_threshold);
00371 Parameters::parse(parameters_, Parameters::kOdomMSCKFTranslationThreshold(), translation_threshold);
00372 Parameters::parse(parameters_, Parameters::kOdomMSCKFTrackingRateThreshold(), tracking_rate_threshold);
00373
00374
00375 Parameters::parse(parameters_, Parameters::kOdomMSCKFOptTranslationThreshold(), msckf_vio::Feature::optimization_config.translation_threshold);
00376
00377
00378 Parameters::parse(parameters_, Parameters::kOdomMSCKFNoiseGyro(), msckf_vio::IMUState::gyro_noise);
00379 Parameters::parse(parameters_, Parameters::kOdomMSCKFNoiseAcc(), msckf_vio::IMUState::acc_noise);
00380 Parameters::parse(parameters_, Parameters::kOdomMSCKFNoiseGyroBias(), msckf_vio::IMUState::gyro_bias_noise);
00381 Parameters::parse(parameters_, Parameters::kOdomMSCKFNoiseAccBias(), msckf_vio::IMUState::acc_bias_noise);
00382 Parameters::parse(parameters_, Parameters::kOdomMSCKFNoiseFeature(), msckf_vio::Feature::observation_noise);
00383
00384
00385 msckf_vio::IMUState::gyro_noise *= msckf_vio::IMUState::gyro_noise;
00386 msckf_vio::IMUState::acc_noise *= msckf_vio::IMUState::acc_noise;
00387 msckf_vio::IMUState::gyro_bias_noise *= msckf_vio::IMUState::gyro_bias_noise;
00388 msckf_vio::IMUState::acc_bias_noise *= msckf_vio::IMUState::acc_bias_noise;
00389 msckf_vio::Feature::observation_noise *= msckf_vio::Feature::observation_noise;
00390
00391
00392
00393
00394
00395
00396
00397
00398
00399
00400
00401
00402
00403 double gyro_bias_cov, acc_bias_cov, velocity_cov;
00404 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovVel(), velocity_cov);
00405 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovGyroBias(), gyro_bias_cov);
00406 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovAccBias(), acc_bias_cov);
00407
00408 double extrinsic_rotation_cov, extrinsic_translation_cov;
00409 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovExRot(), extrinsic_rotation_cov);
00410 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovExTrans(), extrinsic_translation_cov);
00411
00412 state_server.state_cov = Eigen::MatrixXd::Zero(21, 21);
00413 for (int i = 3; i < 6; ++i)
00414 state_server.state_cov(i, i) = gyro_bias_cov;
00415 for (int i = 6; i < 9; ++i)
00416 state_server.state_cov(i, i) = velocity_cov;
00417 for (int i = 9; i < 12; ++i)
00418 state_server.state_cov(i, i) = acc_bias_cov;
00419 for (int i = 15; i < 18; ++i)
00420 state_server.state_cov(i, i) = extrinsic_rotation_cov;
00421 for (int i = 18; i < 21; ++i)
00422 state_server.state_cov(i, i) = extrinsic_translation_cov;
00423
00424
00425 Transform imuCam = model.localTransform().inverse() * imuLocalTransform;
00426 Eigen::Isometry3d T_imu_cam0(imuCam.toEigen4d());
00427 Eigen::Isometry3d T_cam0_imu = T_imu_cam0.inverse();
00428
00429 state_server.imu_state.R_imu_cam0 = T_cam0_imu.linear().transpose();
00430 state_server.imu_state.t_cam0_imu = T_cam0_imu.translation();
00431 Transform cam0cam1;
00432 if(rectified)
00433 {
00434 cam0cam1 = Transform(
00435 1, 0, 0, -model.baseline(),
00436 0, 1, 0, 0,
00437 0, 0, 1, 0);
00438 }
00439 else
00440 {
00441 cam0cam1 = model.stereoTransform();
00442 }
00443 msckf_vio::CAMState::T_cam0_cam1 = cam0cam1.toEigen3d().matrix();
00444 msckf_vio::IMUState::T_imu_body = Transform::getIdentity().toEigen3d().matrix();
00445
00446
00447 Parameters::parse(parameters_, Parameters::kOdomMSCKFMaxCamStateSize(), max_cam_state_size);
00448
00449 UINFO("===========================================");
00450 UINFO("fixed frame id: %s", fixed_frame_id.c_str());
00451 UINFO("child frame id: %s", child_frame_id.c_str());
00452 UINFO("publish tf: %d", publish_tf);
00453 UINFO("frame rate: %f", frame_rate);
00454 UINFO("position std threshold: %f", position_std_threshold);
00455 UINFO("Keyframe rotation threshold: %f", rotation_threshold);
00456 UINFO("Keyframe translation threshold: %f", translation_threshold);
00457 UINFO("Keyframe tracking rate threshold: %f", tracking_rate_threshold);
00458 UINFO("gyro noise: %.10f", msckf_vio::IMUState::gyro_noise);
00459 UINFO("gyro bias noise: %.10f", msckf_vio::IMUState::gyro_bias_noise);
00460 UINFO("acc noise: %.10f", msckf_vio::IMUState::acc_noise);
00461 UINFO("acc bias noise: %.10f", msckf_vio::IMUState::acc_bias_noise);
00462 UINFO("observation noise: %.10f", msckf_vio::Feature::observation_noise);
00463 UINFO("initial velocity: %f, %f, %f",
00464 state_server.imu_state.velocity(0),
00465 state_server.imu_state.velocity(1),
00466 state_server.imu_state.velocity(2));
00467 UINFO("initial gyro bias cov: %f", gyro_bias_cov);
00468 UINFO("initial acc bias cov: %f", acc_bias_cov);
00469 UINFO("initial velocity cov: %f", velocity_cov);
00470 UINFO("initial extrinsic rotation cov: %f",
00471 extrinsic_rotation_cov);
00472 UINFO("initial extrinsic translation cov: %f",
00473 extrinsic_translation_cov);
00474
00475 std::cout << "T_imu_cam0.linear(): " << T_imu_cam0.linear() << std::endl;
00476 std::cout << "T_imu_cam0.translation().transpose(): " << T_imu_cam0.translation().transpose() << std::endl;
00477 std::cout << "CAMState::T_cam0_cam1.linear(): " << msckf_vio::CAMState::T_cam0_cam1.linear() << std::endl;
00478 std::cout << "CAMState::T_cam0_cam1.translation().transpose(): " << msckf_vio::CAMState::T_cam0_cam1.translation().transpose() << std::endl;
00479 std::cout << "IMUState::T_imu_body.linear(): " << msckf_vio::IMUState::T_imu_body.linear() << std::endl;
00480 std::cout << "IMUState::T_imu_body.translation().transpose(): " << msckf_vio::IMUState::T_imu_body.translation().transpose() << std::endl;
00481
00482 UINFO("max camera state #: %d", max_cam_state_size);
00483 UINFO("===========================================");
00484
00485
00486
00487
00488
00489 state_server.continuous_noise_cov =
00490 Eigen::Matrix<double, 12, 12>::Zero();
00491 state_server.continuous_noise_cov.block<3, 3>(0, 0) =
00492 Eigen::Matrix3d::Identity()*msckf_vio::IMUState::gyro_noise;
00493 state_server.continuous_noise_cov.block<3, 3>(3, 3) =
00494 Eigen::Matrix3d::Identity()*msckf_vio::IMUState::gyro_bias_noise;
00495 state_server.continuous_noise_cov.block<3, 3>(6, 6) =
00496 Eigen::Matrix3d::Identity()*msckf_vio::IMUState::acc_noise;
00497 state_server.continuous_noise_cov.block<3, 3>(9, 9) =
00498 Eigen::Matrix3d::Identity()*msckf_vio::IMUState::acc_bias_noise;
00499
00500
00501
00502 for (int i = 1; i < 100; ++i) {
00503 boost::math::chi_squared chi_squared_dist(i);
00504 chi_squared_test_table[i] =
00505 boost::math::quantile(chi_squared_dist, 0.05);
00506 }
00507
00508
00509
00510 }
00511 virtual ~MsckfVioNoROS() {}
00512
00513
00514 nav_msgs::Odometry featureCallback2(
00515 const msckf_vio::CameraMeasurementConstPtr& msg,
00516 pcl::PointCloud<pcl::PointXYZ>::Ptr & localMap) {
00517
00518 nav_msgs::Odometry odom;
00519
00520
00521 if (!is_gravity_set)
00522 {
00523 UINFO("Gravity not set yet... waiting for 200 IMU msgs (%d/200)...", (int)imu_msg_buffer.size());
00524 return odom;
00525 }
00526
00527
00528
00529
00530 if (is_first_img) {
00531 is_first_img = false;
00532 state_server.imu_state.time = msg->header.stamp.toSec();
00533 }
00534
00535
00536
00537
00538
00539
00540
00541
00542 batchImuProcessing(msg->header.stamp.toSec());
00543
00544
00545
00546
00547
00548
00549 stateAugmentation(msg->header.stamp.toSec());
00550
00551
00552
00553
00554
00555
00556 addFeatureObservations(msg);
00557
00558
00559
00560
00561
00562 removeLostFeatures();
00563
00564
00565
00566
00567 pruneCamStateBuffer();
00568
00569
00570
00571
00572
00573 odom = publish(localMap);
00574
00575
00576
00577
00578 onlineReset2();
00579
00580
00581
00582
00583
00584
00585
00586
00587
00588
00589
00590
00591
00592
00593
00594
00595
00596
00597
00598
00599
00600
00601 return odom;
00602 }
00603
00604 void onlineReset2() {
00605
00606
00607
00608 if (position_std_threshold <= 0) return;
00609 static long long int online_reset_counter = 0;
00610
00611
00612
00613 double position_x_std = std::sqrt(state_server.state_cov(12, 12));
00614 double position_y_std = std::sqrt(state_server.state_cov(13, 13));
00615 double position_z_std = std::sqrt(state_server.state_cov(14, 14));
00616
00617 if (position_x_std < position_std_threshold &&
00618 position_y_std < position_std_threshold &&
00619 position_z_std < position_std_threshold) return;
00620
00621 UWARN("Start %lld online reset procedure...",
00622 ++online_reset_counter);
00623 UINFO("Stardard deviation in xyz: %f, %f, %f",
00624 position_x_std, position_y_std, position_z_std);
00625
00626
00627 state_server.cam_states.clear();
00628
00629
00630 map_server.clear();
00631
00632
00633 double gyro_bias_cov, acc_bias_cov, velocity_cov;
00634 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovVel(), velocity_cov);
00635 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovGyroBias(), gyro_bias_cov);
00636 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovAccBias(), acc_bias_cov);
00637
00638 double extrinsic_rotation_cov, extrinsic_translation_cov;
00639 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovExRot(), extrinsic_rotation_cov);
00640 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovExTrans(), extrinsic_translation_cov);
00641
00642
00643 state_server.state_cov = Eigen::MatrixXd::Zero(21, 21);
00644 for (int i = 3; i < 6; ++i)
00645 state_server.state_cov(i, i) = gyro_bias_cov;
00646 for (int i = 6; i < 9; ++i)
00647 state_server.state_cov(i, i) = velocity_cov;
00648 for (int i = 9; i < 12; ++i)
00649 state_server.state_cov(i, i) = acc_bias_cov;
00650 for (int i = 15; i < 18; ++i)
00651 state_server.state_cov(i, i) = extrinsic_rotation_cov;
00652 for (int i = 18; i < 21; ++i)
00653 state_server.state_cov(i, i) = extrinsic_translation_cov;
00654
00655 UWARN("%lld online reset complete...", online_reset_counter);
00656 return;
00657 }
00658
00659 nav_msgs::Odometry publish(pcl::PointCloud<pcl::PointXYZ>::Ptr & feature_msg_ptr) {
00660
00661
00662 const msckf_vio::IMUState& imu_state = state_server.imu_state;
00663 Eigen::Isometry3d T_i_w = Eigen::Isometry3d::Identity();
00664 T_i_w.linear() = msckf_vio::quaternionToRotation(imu_state.orientation).transpose();
00665 T_i_w.translation() = imu_state.position;
00666
00667 Eigen::Isometry3d T_b_w = msckf_vio::IMUState::T_imu_body * T_i_w *
00668 msckf_vio::IMUState::T_imu_body.inverse();
00669 Eigen::Vector3d body_velocity =
00670 msckf_vio::IMUState::T_imu_body.linear() * imu_state.velocity;
00671
00672
00673
00674
00675
00676
00677
00678
00679
00680
00681 nav_msgs::Odometry odom_msg;
00682
00683 odom_msg.header.frame_id = fixed_frame_id;
00684 odom_msg.child_frame_id = child_frame_id;
00685
00686 tf::poseEigenToMsg(T_b_w, odom_msg.pose.pose);
00687 tf::vectorEigenToMsg(body_velocity, odom_msg.twist.twist.linear);
00688
00689
00690 Eigen::Matrix3d P_oo = state_server.state_cov.block<3, 3>(0, 0);
00691 Eigen::Matrix3d P_op = state_server.state_cov.block<3, 3>(0, 12);
00692 Eigen::Matrix3d P_po = state_server.state_cov.block<3, 3>(12, 0);
00693 Eigen::Matrix3d P_pp = state_server.state_cov.block<3, 3>(12, 12);
00694 Eigen::Matrix<double, 6, 6> P_imu_pose = Eigen::Matrix<double, 6, 6>::Zero();
00695 P_imu_pose << P_pp, P_po, P_op, P_oo;
00696
00697 Eigen::Matrix<double, 6, 6> H_pose = Eigen::Matrix<double, 6, 6>::Zero();
00698 H_pose.block<3, 3>(0, 0) = msckf_vio::IMUState::T_imu_body.linear();
00699 H_pose.block<3, 3>(3, 3) = msckf_vio::IMUState::T_imu_body.linear();
00700 Eigen::Matrix<double, 6, 6> P_body_pose = H_pose *
00701 P_imu_pose * H_pose.transpose();
00702
00703 for (int i = 0; i < 6; ++i)
00704 for (int j = 0; j < 6; ++j)
00705 odom_msg.pose.covariance[6*i+j] = P_body_pose(i, j);
00706
00707
00708 Eigen::Matrix3d P_imu_vel = state_server.state_cov.block<3, 3>(6, 6);
00709 Eigen::Matrix3d H_vel = msckf_vio::IMUState::T_imu_body.linear();
00710 Eigen::Matrix3d P_body_vel = H_vel * P_imu_vel * H_vel.transpose();
00711 for (int i = 0; i < 3; ++i)
00712 for (int j = 0; j < 3; ++j)
00713 odom_msg.twist.covariance[i*6+j] = P_body_vel(i, j);
00714
00715
00716
00717
00718
00719 feature_msg_ptr.reset(new pcl::PointCloud<pcl::PointXYZ>());
00720 feature_msg_ptr->header.frame_id = fixed_frame_id;
00721 feature_msg_ptr->height = 1;
00722 for (const auto& item : map_server) {
00723 const auto& feature = item.second;
00724 if (feature.is_initialized) {
00725 Eigen::Vector3d feature_position =
00726 msckf_vio::IMUState::T_imu_body.linear() * feature.position;
00727 feature_msg_ptr->points.push_back(pcl::PointXYZ(
00728 feature_position(0), feature_position(1), feature_position(2)));
00729 }
00730 }
00731 feature_msg_ptr->width = feature_msg_ptr->points.size();
00732
00733
00734
00735 return odom_msg;
00736 }
00737
00738 private:
00739 ParametersMap parameters_;
00740 };
00741 #endif
00742
00743 OdometryMSCKF::OdometryMSCKF(const ParametersMap & parameters) :
00744 Odometry(parameters)
00745 #ifdef RTABMAP_MSCKF_VIO
00746 ,
00747 imageProcessor_(0),
00748 msckf_(0),
00749 parameters_(parameters),
00750 flipXY_(-1, 0, 0, 0, 0, -1, 0, 0, 0, 0, 1, 0),
00751 previousPose_(Transform::getIdentity()),
00752 initGravity_(false)
00753 #endif
00754 {
00755 }
00756
00757 OdometryMSCKF::~OdometryMSCKF()
00758 {
00759 UDEBUG("");
00760 #ifdef RTABMAP_MSCKF_VIO
00761 delete imageProcessor_;
00762 delete msckf_;
00763 #endif
00764 }
00765
00766 void OdometryMSCKF::reset(const Transform & initialPose)
00767 {
00768 Odometry::reset(initialPose);
00769 #ifdef RTABMAP_MSCKF_VIO
00770 if(!initGravity_)
00771 {
00772 if(imageProcessor_)
00773 {
00774 delete imageProcessor_;
00775 imageProcessor_ = 0;
00776 }
00777 if(msckf_)
00778 {
00779 delete msckf_;
00780 msckf_ = 0;
00781 }
00782 lastImu_ = IMU();
00783 previousPose_.setIdentity();
00784 }
00785 initGravity_ = false;
00786 #endif
00787 }
00788
00789
00790 Transform OdometryMSCKF::computeTransform(
00791 SensorData & data,
00792 const Transform & guess,
00793 OdometryInfo * info)
00794 {
00795 UDEBUG("");
00796 Transform t;
00797
00798 #ifdef RTABMAP_MSCKF_VIO
00799 UTimer timer;
00800
00801 if(!data.imu().empty())
00802 {
00803 UDEBUG("IMU update stamp=%f acc=%f %f %f gyr=%f %f %f", data.stamp(),
00804 data.imu().linearAcceleration()[0],
00805 data.imu().linearAcceleration()[1],
00806 data.imu().linearAcceleration()[2],
00807 data.imu().angularVelocity()[0],
00808 data.imu().angularVelocity()[1],
00809 data.imu().angularVelocity()[2]);
00810 if(imageProcessor_ && msckf_)
00811 {
00812 sensor_msgs::ImuPtr msg(new sensor_msgs::Imu);
00813 msg->angular_velocity.x = data.imu().angularVelocity()[0];
00814 msg->angular_velocity.y = data.imu().angularVelocity()[1];
00815 msg->angular_velocity.z = data.imu().angularVelocity()[2];
00816 msg->linear_acceleration.x = data.imu().linearAcceleration()[0];
00817 msg->linear_acceleration.y = data.imu().linearAcceleration()[1];
00818 msg->linear_acceleration.z = data.imu().linearAcceleration()[2];
00819 msg->header.stamp.fromSec(data.stamp());
00820 imageProcessor_->imuCallback(msg);
00821 msckf_->imuCallback(msg);
00822 }
00823 else
00824 {
00825 UWARN("Ignoring IMU, waiting for an image to initialize...");
00826 lastImu_ = data.imu();
00827 }
00828 }
00829
00830 if(!data.imageRaw().empty() && !data.rightRaw().empty())
00831 {
00832 UDEBUG("Image update stamp=%f", data.stamp());
00833 if(data.stereoCameraModel().isValidForProjection())
00834 {
00835 if(msckf_ == 0)
00836 {
00837 UINFO("Initialization");
00838 if(lastImu_.empty())
00839 {
00840 UWARN("Ignoring Image, waiting for imu to initialize...");
00841 return t;
00842 }
00843 UINFO("Creating ImageProcessorNoROS...");
00844 imageProcessor_ = new ImageProcessorNoROS(
00845 parameters_,
00846 lastImu_.localTransform(),
00847 data.stereoCameraModel(),
00848 this->imagesAlreadyRectified());
00849 UINFO("Creating MsckfVioNoROS...");
00850 msckf_ = new MsckfVioNoROS(
00851 parameters_,
00852 lastImu_.localTransform(),
00853 data.stereoCameraModel(),
00854 this->imagesAlreadyRectified());
00855 }
00856
00857
00858 cv_bridge::CvImage cam0;
00859 cv_bridge::CvImage cam1;
00860 cam0.header.stamp.fromSec(data.stamp());
00861 cam1.header.stamp.fromSec(data.stamp());
00862
00863 if(data.imageRaw().type() == CV_8UC3)
00864 {
00865 cv::cvtColor(data.imageRaw(), cam0.image, CV_BGR2GRAY);
00866 }
00867 else
00868 {
00869 cam0.image = data.imageRaw();
00870 }
00871 if(data.rightRaw().type() == CV_8UC3)
00872 {
00873 cv::cvtColor(data.rightRaw(), cam1.image, CV_BGR2GRAY);
00874 }
00875 else
00876 {
00877 cam1.image = data.rightRaw();
00878 }
00879
00880 sensor_msgs::ImagePtr cam0Msg(new sensor_msgs::Image);
00881 sensor_msgs::ImagePtr cam1Msg(new sensor_msgs::Image);
00882 cam0.toImageMsg(*cam0Msg);
00883 cam1.toImageMsg(*cam1Msg);
00884 cam0Msg->encoding = sensor_msgs::image_encodings::MONO8;
00885 cam1Msg->encoding = sensor_msgs::image_encodings::MONO8;
00886
00887 msckf_vio::CameraMeasurementPtr measurements = imageProcessor_->stereoCallback2(cam0Msg, cam1Msg);
00888 pcl::PointCloud<pcl::PointXYZ>::Ptr localMap;
00889 nav_msgs::Odometry odom = msckf_->featureCallback2(measurements, localMap);
00890
00891 Transform p = Transform(
00892 odom.pose.pose.position.x,
00893 odom.pose.pose.position.y,
00894 odom.pose.pose.position.z,
00895 odom.pose.pose.orientation.x,
00896 odom.pose.pose.orientation.y,
00897 odom.pose.pose.orientation.z,
00898 odom.pose.pose.orientation.w);
00899
00900 if(!p.isNull())
00901 {
00902
00903 p = flipXY_*p*lastImu_.localTransform();
00904
00905 if(this->getPose().rotation().isIdentity())
00906 {
00907 initGravity_ = true;
00908 this->reset(this->getPose()*p.rotation());
00909 }
00910
00911 if(previousPose_.isIdentity())
00912 {
00913 previousPose_ = p;
00914 }
00915
00916
00917 Transform previousPoseInv = previousPose_.inverse();
00918 t = previousPoseInv*p;
00919 previousPose_ = p;
00920
00921 if(info)
00922 {
00923 info->type = this->getType();
00924 info->features = measurements->features.size();
00925
00926 info->reg.covariance = cv::Mat::zeros(6, 6, CV_64FC1);
00927 cv::Mat twistCov(6,6,CV_64FC1, odom.twist.covariance.elems);
00928
00929
00930 cv::Matx31f covWorldFrame(twistCov.at<double>(0, 0),
00931 twistCov.at<double>(1, 1),
00932 twistCov.at<double>(2, 2));
00933 cv::Matx31f covBaseFrame = cv::Matx33f(previousPoseInv.rotationMatrix()) * covWorldFrame;
00934
00935 info->reg.covariance.at<double>(0, 0) = fabs(covBaseFrame.val[0])/10.0;
00936 info->reg.covariance.at<double>(1, 1) = fabs(covBaseFrame.val[1])/10.0;
00937 info->reg.covariance.at<double>(2, 2) = fabs(covBaseFrame.val[2])/10.0;
00938 if(info->reg.covariance.at<double>(0, 0) < 0.0001)
00939 {
00940 info->reg.covariance.at<double>(0, 0) = 0.0001;
00941 }
00942 if(info->reg.covariance.at<double>(1, 1) < 0.0001)
00943 {
00944 info->reg.covariance.at<double>(1, 1) = 0.0001;
00945 }
00946 if(info->reg.covariance.at<double>(2, 2) < 0.0001)
00947 {
00948 info->reg.covariance.at<double>(2, 2) = 0.0001;
00949 }
00950 info->reg.covariance.at<double>(3, 3) = msckf_vio::IMUState::gyro_noise*10.0;
00951 info->reg.covariance.at<double>(4, 4) = info->reg.covariance.at<double>(3, 3);
00952 info->reg.covariance.at<double>(5, 5) = info->reg.covariance.at<double>(3, 3);
00953
00954 if(this->isInfoDataFilled())
00955 {
00956 if(localMap.get() && localMap->size())
00957 {
00958 Eigen::Affine3f flip = (this->getPose()*previousPoseInv*flipXY_).toEigen3f();
00959 for(unsigned int i=0; i<localMap->size(); ++i)
00960 {
00961 pcl::PointXYZ pt = pcl::transformPoint(localMap->at(i), flip);
00962 info->localMap.insert(std::make_pair(i, cv::Point3f(pt.x, pt.y, pt.z)));
00963 }
00964 }
00965 if(this->imagesAlreadyRectified())
00966 {
00967 info->newCorners.resize(measurements->features.size());
00968 float fx = data.stereoCameraModel().left().fx();
00969 float fy = data.stereoCameraModel().left().fy();
00970 float cx = data.stereoCameraModel().left().cx();
00971 float cy = data.stereoCameraModel().left().cy();
00972 info->reg.inliersIDs.resize(measurements->features.size());
00973 for(unsigned int i=0; i<measurements->features.size(); ++i)
00974 {
00975 info->newCorners[i].x = measurements->features[i].u0*fx+cx;
00976 info->newCorners[i].y = measurements->features[i].v0*fy+cy;
00977 info->reg.inliersIDs[i] = i;
00978 }
00979 }
00980 }
00981 }
00982 }
00983
00984 UINFO("Odom update time = %fs p=%s", timer.elapsed(), p.prettyPrint().c_str());
00985 }
00986 }
00987
00988 #else
00989 UERROR("RTAB-Map is not built with MSCKF_VIO support! Select another visual odometry approach.");
00990 #endif
00991 return t;
00992 }
00993
00994 }