35 #include <opencv2/imgproc/types_c.h>    37 #ifdef RTABMAP_MSCKF_VIO    38 #include <msckf_vio/image_processor.h>    39 #include <msckf_vio/msckf_vio.h>    40 #include <msckf_vio/math_utils.hpp>    41 #include <eigen_conversions/eigen_msg.h>    42 #include <boost/math/distributions/chi_squared.hpp>    43 #include <pcl/common/transforms.h>    48 #ifdef RTABMAP_MSCKF_VIO    49 class ImageProcessorNoROS: 
public msckf_vio::ImageProcessor
    54                         const Transform & imuLocalTransform,
    55                         const StereoCameraModel & 
model,
    57                                 msckf_vio::ImageProcessor(0)
    61                 if(model.left().D_raw().cols == 6)
    64                         cam0_distortion_model = 
"equidistant";
    65                         cam0_distortion_coeffs[0] = rectified?0:model.left().D_raw().at<
double>(0,0);
    66                         cam0_distortion_coeffs[1] = rectified?0:model.left().D_raw().at<
double>(0,1);
    67                         cam0_distortion_coeffs[2] = rectified?0:model.left().D_raw().at<
double>(0,4);
    68                         cam0_distortion_coeffs[3] = rectified?0:model.left().D_raw().at<
double>(0,5);
    73                         cam0_distortion_model = 
"radtan";
    74                         cam0_distortion_coeffs[0] = rectified?0:model.left().D_raw().at<
double>(0,0);
    75                         cam0_distortion_coeffs[1] = rectified?0:model.left().D_raw().at<
double>(0,1);
    76                         cam0_distortion_coeffs[2] = rectified?0:model.left().D_raw().at<
double>(0,2);
    77                         cam0_distortion_coeffs[3] = rectified?0:model.left().D_raw().at<
double>(0,3);
    79                 if(model.right().D_raw().cols == 6)
    82                         cam1_distortion_model = 
"equidistant";
    83                         cam1_distortion_coeffs[0] = rectified?0:model.right().D_raw().at<
double>(0,0);
    84                         cam1_distortion_coeffs[1] = rectified?0:model.right().D_raw().at<
double>(0,1);
    85                         cam1_distortion_coeffs[2] = rectified?0:model.right().D_raw().at<
double>(0,4);
    86                         cam1_distortion_coeffs[3] = rectified?0:model.right().D_raw().at<
double>(0,5);
    91                         cam1_distortion_model = 
"radtan";
    92                         cam1_distortion_coeffs[0] = rectified?0:model.right().D_raw().at<
double>(0,0);
    93                         cam1_distortion_coeffs[1] = rectified?0:model.right().D_raw().at<
double>(0,1);
    94                         cam1_distortion_coeffs[2] = rectified?0:model.right().D_raw().at<
double>(0,2);
    95                         cam1_distortion_coeffs[3] = rectified?0:model.right().D_raw().at<
double>(0,3);
    98                 cam0_resolution[0] = model.left().imageWidth();
    99                 cam0_resolution[1] = model.left().imageHeight();
   101                 cam1_resolution[0] = model.right().imageWidth();
   102                 cam1_resolution[1] = model.right().imageHeight();
   104                 cam0_intrinsics[0] = rectified?model.left().fx():model.left().K_raw().at<
double>(0,0);
   105                 cam0_intrinsics[1] = rectified?model.left().fy():model.left().K_raw().at<
double>(1,1);
   106                 cam0_intrinsics[2] = rectified?model.left().cx():model.left().K_raw().at<
double>(0,2);
   107                 cam0_intrinsics[3] = rectified?model.left().cy():model.left().K_raw().at<
double>(1,2);
   109                 cam1_intrinsics[0] = rectified?model.right().fx():model.right().K_raw().at<
double>(0,0);
   110                 cam1_intrinsics[1] = rectified?model.right().fy():model.right().K_raw().at<
double>(1,1);
   111                 cam1_intrinsics[2] = rectified?model.right().cx():model.right().K_raw().at<
double>(0,2);
   112                 cam1_intrinsics[3] = rectified?model.right().cy():model.right().K_raw().at<
double>(1,2);
   114                 UINFO(
"Local transform=%s", model.localTransform().prettyPrint().c_str());
   115                 UINFO(
"imuLocalTransform=%s", imuLocalTransform.prettyPrint().c_str());
   116                 Transform imuCam = model.localTransform().inverse() * imuLocalTransform;
   117                 UINFO(
"imuCam=%s", imuCam.prettyPrint().c_str());
   118                 cv::Mat     T_imu_cam0 = imuCam.dataMatrix();
   119                 cv::Matx33d R_imu_cam0(T_imu_cam0(cv::Rect(0,0,3,3)));
   120                 cv::Vec3d   t_imu_cam0 = T_imu_cam0(cv::Rect(3,0,1,3));
   121                 R_cam0_imu = R_imu_cam0.t();
   122                 t_cam0_imu = -R_imu_cam0.t() * t_imu_cam0;
   127                         cam0cam1 = Transform(
   128                                         1, 0, 0, -model.baseline(),
   134                         cam0cam1 = model.stereoTransform();
   136                 UINFO(
"cam0cam1=%s", cam0cam1.prettyPrint().c_str());
   138                 Transform imuCam1 = cam0cam1 * imuCam;
   139                 cv::Mat T_imu_cam1 = imuCam1.dataMatrix();
   140                 cv::Matx33d R_imu_cam1(T_imu_cam1(cv::Rect(0,0,3,3)));
   141                 cv::Vec3d   t_imu_cam1 = T_imu_cam1(cv::Rect(3,0,1,3));
   142                 R_cam1_imu = R_imu_cam1.t();
   143                 t_cam1_imu = -R_imu_cam1.t() * t_imu_cam1;
   147                 uInsert(parameters, parameters_in);
   149                 Parameters::parse(parameters, Parameters::kOdomMSCKFGridRow(), processor_config.grid_row); 
   150                 Parameters::parse(parameters, Parameters::kOdomMSCKFGridCol(), processor_config.grid_col); 
   151                 Parameters::parse(parameters, Parameters::kOdomMSCKFGridMinFeatureNum(), processor_config.grid_min_feature_num); 
   152                 Parameters::parse(parameters, Parameters::kOdomMSCKFGridMaxFeatureNum(), processor_config.grid_max_feature_num); 
   153                 Parameters::parse(parameters, Parameters::kOdomMSCKFPyramidLevels(), processor_config.pyramid_levels); 
   154                 Parameters::parse(parameters, Parameters::kOdomMSCKFPatchSize(), processor_config.patch_size); 
   155                 Parameters::parse(parameters, Parameters::kOdomMSCKFFastThreshold(), processor_config.fast_threshold); 
   156                 Parameters::parse(parameters, Parameters::kOdomMSCKFMaxIteration(), processor_config.max_iteration); 
   157                 Parameters::parse(parameters, Parameters::kOdomMSCKFTrackPrecision(), processor_config.track_precision); 
   158                 Parameters::parse(parameters, Parameters::kOdomMSCKFRansacThreshold(), processor_config.ransac_threshold); 
   159                 Parameters::parse(parameters, Parameters::kOdomMSCKFStereoThreshold(), processor_config.stereo_threshold); 
   161                 UINFO(
"===========================================");
   162                 UINFO(
"cam0_resolution: %d, %d",
   163                                 cam0_resolution[0], cam0_resolution[1]);
   164                 UINFO(
"cam0_intrinscs: %f, %f, %f, %f",
   165                                 cam0_intrinsics[0], cam0_intrinsics[1],
   166                                 cam0_intrinsics[2], cam0_intrinsics[3]);
   167                 UINFO(
"cam0_distortion_model: %s",
   168                                 cam0_distortion_model.c_str());
   169                 UINFO(
"cam0_distortion_coefficients: %f, %f, %f, %f",
   170                                 cam0_distortion_coeffs[0], cam0_distortion_coeffs[1],
   171                                 cam0_distortion_coeffs[2], cam0_distortion_coeffs[3]);
   173                 UINFO(
"cam1_resolution: %d, %d",
   174                                 cam1_resolution[0], cam1_resolution[1]);
   175                 UINFO(
"cam1_intrinscs: %f, %f, %f, %f",
   176                                 cam1_intrinsics[0], cam1_intrinsics[1],
   177                                 cam1_intrinsics[2], cam1_intrinsics[3]);
   178                 UINFO(
"cam1_distortion_model: %s",
   179                                 cam1_distortion_model.c_str());
   180                 UINFO(
"cam1_distortion_coefficients: %f, %f, %f, %f",
   181                                 cam1_distortion_coeffs[0], cam1_distortion_coeffs[1],
   182                                 cam1_distortion_coeffs[2], cam1_distortion_coeffs[3]);
   184                 std::cout << 
"R_imu_cam0: " << R_imu_cam0 << std::endl;
   185                 std::cout << 
"t_imu_cam0.t(): " << t_imu_cam0.t() << std::endl;
   186                 std::cout << 
"R_imu_cam1: " << R_imu_cam1 << std::endl;
   187                 std::cout << 
"t_imu_cam1.t(): " << t_imu_cam1.t() << std::endl;
   189                 UINFO(
"grid_row: %d",
   190                                 processor_config.grid_row);
   191                 UINFO(
"grid_col: %d",
   192                                 processor_config.grid_col);
   193                 UINFO(
"grid_min_feature_num: %d",
   194                                 processor_config.grid_min_feature_num);
   195                 UINFO(
"grid_max_feature_num: %d",
   196                                 processor_config.grid_max_feature_num);
   197                 UINFO(
"pyramid_levels: %d",
   198                                 processor_config.pyramid_levels);
   199                 UINFO(
"patch_size: %d",
   200                                 processor_config.patch_size);
   201                 UINFO(
"fast_threshold: %d",
   202                                 processor_config.fast_threshold);
   203                 UINFO(
"max_iteration: %d",
   204                                 processor_config.max_iteration);
   205                 UINFO(
"track_precision: %f",
   206                                 processor_config.track_precision);
   207                 UINFO(
"ransac_threshold: %f",
   208                                 processor_config.ransac_threshold);
   209                 UINFO(
"stereo_threshold: %f",
   210                                 processor_config.stereo_threshold);
   211                 UINFO(
"===========================================");
   214                 detector_ptr = cv::FastFeatureDetector::create(
   215                   processor_config.fast_threshold);
   218         virtual ~ImageProcessorNoROS() {}
   220         msckf_vio::CameraMeasurementPtr stereoCallback2(
   221                         const sensor_msgs::ImageConstPtr& cam0_img,
   222                         const sensor_msgs::ImageConstPtr& cam1_img) {
   234                 createImagePyramids();
   239                         initializeFirstFrame();
   242                         is_first_img = 
false;
   282                 msckf_vio::CameraMeasurementPtr measurements = publish();
   287                 cam0_prev_img_ptr = cam0_curr_img_ptr;
   288                 prev_features_ptr = curr_features_ptr;
   289                 std::swap(prev_cam0_pyramid_, curr_cam0_pyramid_);
   292                 curr_features_ptr.reset(
new GridFeatures());
   293                 for (
int code = 0; code <
   294                 processor_config.grid_row*processor_config.grid_col; ++code) {
   295                         (*curr_features_ptr)[code] = std::vector<FeatureMetaData>(0);
   301         msckf_vio::CameraMeasurementPtr publish() {
   304                 msckf_vio::CameraMeasurementPtr feature_msg_ptr(
new msckf_vio::CameraMeasurement);
   305                 feature_msg_ptr->header.stamp = cam0_curr_img_ptr->header.stamp;
   307                 std::vector<FeatureIDType> curr_ids(0);
   308                 std::vector<cv::Point2f> curr_cam0_points(0);
   309                 std::vector<cv::Point2f> curr_cam1_points(0);
   311                 for (
const auto& grid_features : (*curr_features_ptr)) {
   312                         for (
const auto& feature : grid_features.second) {
   313                                 curr_ids.push_back(feature.id);
   314                                 curr_cam0_points.push_back(feature.cam0_point);
   315                                 curr_cam1_points.push_back(feature.cam1_point);
   319                 std::vector<cv::Point2f> curr_cam0_points_undistorted(0);
   320                 std::vector<cv::Point2f> curr_cam1_points_undistorted(0);
   323                                 curr_cam0_points, cam0_intrinsics, cam0_distortion_model,
   324                                 cam0_distortion_coeffs, curr_cam0_points_undistorted);
   326                                 curr_cam1_points, cam1_intrinsics, cam1_distortion_model,
   327                                 cam1_distortion_coeffs, curr_cam1_points_undistorted);
   329                 for (
unsigned int i = 0; i < curr_ids.size(); ++i) {
   330                         feature_msg_ptr->features.push_back(msckf_vio::FeatureMeasurement());
   331                         feature_msg_ptr->features[i].id = curr_ids[i];
   332                         feature_msg_ptr->features[i].u0 = curr_cam0_points_undistorted[i].x;
   333                         feature_msg_ptr->features[i].v0 = curr_cam0_points_undistorted[i].y;
   334                         feature_msg_ptr->features[i].u1 = curr_cam1_points_undistorted[i].x;
   335                         feature_msg_ptr->features[i].v1 = curr_cam1_points_undistorted[i].y;
   349                 return feature_msg_ptr;
   353 class MsckfVioNoROS: 
public msckf_vio::MsckfVio
   356         EIGEN_MAKE_ALIGNED_OPERATOR_NEW
   359                         const Transform & imuLocalTransform,
   360                         const StereoCameraModel & model,
   362                         msckf_vio::MsckfVio(0)
   367                 uInsert(parameters_, parameters_in);
   372                 Parameters::parse(parameters_, Parameters::kOdomMSCKFPositionStdThreshold(), position_std_threshold); 
   374                 Parameters::parse(parameters_, Parameters::kOdomMSCKFRotationThreshold(), rotation_threshold); 
   375                 Parameters::parse(parameters_, Parameters::kOdomMSCKFTranslationThreshold(), translation_threshold); 
   376                 Parameters::parse(parameters_, Parameters::kOdomMSCKFTrackingRateThreshold(), tracking_rate_threshold); 
   379                 Parameters::parse(parameters_, Parameters::kOdomMSCKFOptTranslationThreshold(), msckf_vio::Feature::optimization_config.translation_threshold); 
   382                 Parameters::parse(parameters_, Parameters::kOdomMSCKFNoiseGyro(), msckf_vio::IMUState::gyro_noise); 
   383                 Parameters::parse(parameters_, Parameters::kOdomMSCKFNoiseAcc(), msckf_vio::IMUState::acc_noise); 
   384                 Parameters::parse(parameters_, Parameters::kOdomMSCKFNoiseGyroBias(), msckf_vio::IMUState::gyro_bias_noise); 
   385                 Parameters::parse(parameters_, Parameters::kOdomMSCKFNoiseAccBias(), msckf_vio::IMUState::acc_bias_noise); 
   386                 Parameters::parse(parameters_, Parameters::kOdomMSCKFNoiseFeature(), msckf_vio::Feature::observation_noise); 
   389                 msckf_vio::IMUState::gyro_noise *= msckf_vio::IMUState::gyro_noise;
   390                 msckf_vio::IMUState::acc_noise *= msckf_vio::IMUState::acc_noise;
   391                 msckf_vio::IMUState::gyro_bias_noise *= msckf_vio::IMUState::gyro_bias_noise;
   392                 msckf_vio::IMUState::acc_bias_noise *= msckf_vio::IMUState::acc_bias_noise;
   393                 msckf_vio::Feature::observation_noise *= msckf_vio::Feature::observation_noise;
   407                 double gyro_bias_cov, acc_bias_cov, velocity_cov;
   408                 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovVel(), velocity_cov); 
   409                 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovGyroBias(), gyro_bias_cov); 
   410                 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovAccBias(), acc_bias_cov); 
   412                 double extrinsic_rotation_cov, extrinsic_translation_cov;
   413                 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovExRot(), extrinsic_rotation_cov); 
   414                 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovExTrans(), extrinsic_translation_cov); 
   416                 state_server.state_cov = Eigen::MatrixXd::Zero(21, 21);
   417                 for (
int i = 3; i < 6; ++i)
   418                         state_server.state_cov(i, i) = gyro_bias_cov;
   419                 for (
int i = 6; i < 9; ++i)
   420                         state_server.state_cov(i, i) = velocity_cov;
   421                 for (
int i = 9; i < 12; ++i)
   422                         state_server.state_cov(i, i) = acc_bias_cov;
   423                 for (
int i = 15; i < 18; ++i)
   424                         state_server.state_cov(i, i) = extrinsic_rotation_cov;
   425                 for (
int i = 18; i < 21; ++i)
   426                         state_server.state_cov(i, i) = extrinsic_translation_cov;
   429                 UINFO(
"Local transform=%s", model.localTransform().prettyPrint().c_str());
   430                 UINFO(
"imuLocalTransform=%s", imuLocalTransform.prettyPrint().c_str());
   431                 Transform imuCam = model.localTransform().inverse() * imuLocalTransform;
   432                 UINFO(
"imuCam=%s", imuCam.prettyPrint().c_str());
   433                 Eigen::Isometry3d T_imu_cam0(imuCam.toEigen4d());
   434                 Eigen::Isometry3d T_cam0_imu = T_imu_cam0.inverse();
   436                 state_server.imu_state.R_imu_cam0 = T_cam0_imu.linear().transpose();
   437                 state_server.imu_state.t_cam0_imu = T_cam0_imu.translation();
   441                         cam0cam1 = Transform(
   442                                         1, 0, 0, -model.baseline(),
   448                         cam0cam1 = model.stereoTransform();
   450                 UINFO(
"cam0cam1=%s", cam0cam1.prettyPrint().c_str());
   451                 msckf_vio::CAMState::T_cam0_cam1 = cam0cam1.toEigen3d().matrix();
   452                 msckf_vio::IMUState::T_imu_body = imuLocalTransform.toEigen3d().matrix();
   455                 Parameters::parse(parameters_, Parameters::kOdomMSCKFMaxCamStateSize(), max_cam_state_size); 
   457                 UINFO(
"===========================================");
   458                 UINFO(
"fixed frame id: %s", fixed_frame_id.c_str());
   459                 UINFO(
"child frame id: %s", child_frame_id.c_str());
   460                 UINFO(
"publish tf: %d", publish_tf);
   461                 UINFO(
"frame rate: %f", frame_rate);
   462                 UINFO(
"position std threshold: %f", position_std_threshold);
   463                 UINFO(
"Keyframe rotation threshold: %f", rotation_threshold);
   464                 UINFO(
"Keyframe translation threshold: %f", translation_threshold);
   465                 UINFO(
"Keyframe tracking rate threshold: %f", tracking_rate_threshold);
   466                 UINFO(
"gyro noise: %.10f", msckf_vio::IMUState::gyro_noise);
   467                 UINFO(
"gyro bias noise: %.10f", msckf_vio::IMUState::gyro_bias_noise);
   468                 UINFO(
"acc noise: %.10f", msckf_vio::IMUState::acc_noise);
   469                 UINFO(
"acc bias noise: %.10f", msckf_vio::IMUState::acc_bias_noise);
   470                 UINFO(
"observation noise: %.10f", msckf_vio::Feature::observation_noise);
   471                 UINFO(
"initial velocity: %f, %f, %f",
   472                                 state_server.imu_state.velocity(0),
   473                                 state_server.imu_state.velocity(1),
   474                                 state_server.imu_state.velocity(2));
   475                 UINFO(
"initial gyro bias cov: %f", gyro_bias_cov);
   476                 UINFO(
"initial acc bias cov: %f", acc_bias_cov);
   477                 UINFO(
"initial velocity cov: %f", velocity_cov);
   478                 UINFO(
"initial extrinsic rotation cov: %f",
   479                                 extrinsic_rotation_cov);
   480                 UINFO(
"initial extrinsic translation cov: %f",
   481                                 extrinsic_translation_cov);
   483                 std::cout << 
"T_imu_cam0.linear(): " << T_imu_cam0.linear() << std::endl;
   484                 std::cout << 
"T_imu_cam0.translation().transpose(): " << T_imu_cam0.translation().transpose() << std::endl;
   485                 std::cout << 
"CAMState::T_cam0_cam1.linear(): " << msckf_vio::CAMState::T_cam0_cam1.linear() << std::endl;
   486                 std::cout << 
"CAMState::T_cam0_cam1.translation().transpose(): " << msckf_vio::CAMState::T_cam0_cam1.translation().transpose() << std::endl;
   487                 std::cout << 
"IMUState::T_imu_body.linear(): " << msckf_vio::IMUState::T_imu_body.linear() << std::endl;
   488                 std::cout << 
"IMUState::T_imu_body.translation().transpose(): " << msckf_vio::IMUState::T_imu_body.translation().transpose() << std::endl;
   490                 UINFO(
"max camera state #: %d", max_cam_state_size);
   491                 UINFO(
"===========================================");
   497                 state_server.continuous_noise_cov =
   498                                 Eigen::Matrix<double, 12, 12>::Zero();
   499                 state_server.continuous_noise_cov.block<3, 3>(0, 0) =
   500                                 Eigen::Matrix3d::Identity()*msckf_vio::IMUState::gyro_noise;
   501                 state_server.continuous_noise_cov.block<3, 3>(3, 3) =
   502                                 Eigen::Matrix3d::Identity()*msckf_vio::IMUState::gyro_bias_noise;
   503                 state_server.continuous_noise_cov.block<3, 3>(6, 6) =
   504                                 Eigen::Matrix3d::Identity()*msckf_vio::IMUState::acc_noise;
   505                 state_server.continuous_noise_cov.block<3, 3>(9, 9) =
   506                                 Eigen::Matrix3d::Identity()*msckf_vio::IMUState::acc_bias_noise;
   510                 for (
int i = 1; i < 100; ++i) {
   511                         boost::math::chi_squared chi_squared_dist(i);
   512                         chi_squared_test_table[i] =
   513                                         boost::math::quantile(chi_squared_dist, 0.05);
   519         virtual ~MsckfVioNoROS() {}
   522         nav_msgs::Odometry featureCallback2(
   523                         const msckf_vio::CameraMeasurementConstPtr& msg,
   524                         pcl::PointCloud<pcl::PointXYZ>::Ptr & localMap) {
   526                 nav_msgs::Odometry odom;
   531                         UINFO(
"Gravity not set yet... waiting for 200 IMU msgs (%d/200)...", (
int)imu_msg_buffer.size());
   539                         is_first_img = 
false;
   540                         state_server.imu_state.time = msg->header.stamp.toSec();
   550                 batchImuProcessing(msg->header.stamp.toSec());
   557                 stateAugmentation(msg->header.stamp.toSec());
   564                 addFeatureObservations(msg);
   570                 removeLostFeatures();
   575                 pruneCamStateBuffer();
   581                 odom = publish(localMap);
   612         void onlineReset2() {
   616                 if (position_std_threshold <= 0) 
return;
   617                 static long long int online_reset_counter = 0;
   621                 double position_x_std = 
std::sqrt(state_server.state_cov(12, 12));
   622                 double position_y_std = 
std::sqrt(state_server.state_cov(13, 13));
   623                 double position_z_std = 
std::sqrt(state_server.state_cov(14, 14));
   625                 if (position_x_std < position_std_threshold &&
   626                                 position_y_std < position_std_threshold &&
   627                                 position_z_std < position_std_threshold) 
return;
   629                 UWARN(
"Start %lld online reset procedure...",
   630                                 ++online_reset_counter);
   631                 UINFO(
"Stardard deviation in xyz: %f, %f, %f",
   632                                 position_x_std, position_y_std, position_z_std);
   635                 state_server.cam_states.clear();
   641                 double gyro_bias_cov, acc_bias_cov, velocity_cov;
   642                 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovVel(), velocity_cov); 
   643                 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovGyroBias(), gyro_bias_cov); 
   644                 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovAccBias(), acc_bias_cov); 
   646                 double extrinsic_rotation_cov, extrinsic_translation_cov;
   647                 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovExRot(), extrinsic_rotation_cov); 
   648                 Parameters::parse(parameters_, Parameters::kOdomMSCKFInitCovExTrans(), extrinsic_translation_cov); 
   651                 state_server.state_cov = Eigen::MatrixXd::Zero(21, 21);
   652                 for (
int i = 3; i < 6; ++i)
   653                         state_server.state_cov(i, i) = gyro_bias_cov;
   654                 for (
int i = 6; i < 9; ++i)
   655                         state_server.state_cov(i, i) = velocity_cov;
   656                 for (
int i = 9; i < 12; ++i)
   657                         state_server.state_cov(i, i) = acc_bias_cov;
   658                 for (
int i = 15; i < 18; ++i)
   659                         state_server.state_cov(i, i) = extrinsic_rotation_cov;
   660                 for (
int i = 18; i < 21; ++i)
   661                         state_server.state_cov(i, i) = extrinsic_translation_cov;
   663                 UWARN(
"%lld online reset complete...", online_reset_counter);
   667         nav_msgs::Odometry publish(pcl::PointCloud<pcl::PointXYZ>::Ptr & feature_msg_ptr) {
   670                 const msckf_vio::IMUState& imu_state = state_server.imu_state;
   671                 Eigen::Isometry3d T_i_w = Eigen::Isometry3d::Identity();
   672                 T_i_w.linear() = msckf_vio::quaternionToRotation(imu_state.orientation).transpose();
   673                 T_i_w.translation() = imu_state.position;
   675                 Eigen::Isometry3d T_b_w = msckf_vio::IMUState::T_imu_body * T_i_w *
   676                                 msckf_vio::IMUState::T_imu_body.inverse();
   677                 Eigen::Vector3d body_velocity =
   678                                 msckf_vio::IMUState::T_imu_body.linear() * imu_state.velocity;
   689                 nav_msgs::Odometry odom_msg;
   691                 odom_msg.header.frame_id = fixed_frame_id;
   692                 odom_msg.child_frame_id = child_frame_id;
   694                 tf::poseEigenToMsg(T_b_w, odom_msg.pose.pose);
   695                 tf::vectorEigenToMsg(body_velocity, odom_msg.twist.twist.linear);
   698                 Eigen::Matrix3d P_oo = state_server.state_cov.block<3, 3>(0, 0);
   699                 Eigen::Matrix3d P_op = state_server.state_cov.block<3, 3>(0, 12);
   700                 Eigen::Matrix3d P_po = state_server.state_cov.block<3, 3>(12, 0);
   701                 Eigen::Matrix3d P_pp = state_server.state_cov.block<3, 3>(12, 12);
   702                 Eigen::Matrix<double, 6, 6> P_imu_pose = Eigen::Matrix<double, 6, 6>::Zero();
   703                 P_imu_pose << P_pp, P_po, P_op, P_oo;
   705                 Eigen::Matrix<double, 6, 6> H_pose = Eigen::Matrix<double, 6, 6>::Zero();
   706                 H_pose.block<3, 3>(0, 0) = msckf_vio::IMUState::T_imu_body.linear();
   707                 H_pose.block<3, 3>(3, 3) = msckf_vio::IMUState::T_imu_body.linear();
   708                 Eigen::Matrix<double, 6, 6> P_body_pose = H_pose *
   709                                 P_imu_pose * H_pose.transpose();
   711                 for (
int i = 0; i < 6; ++i)
   712                         for (
int j = 0; j < 6; ++j)
   713                                 odom_msg.pose.covariance[6*i+j] = P_body_pose(i, j);
   716                 Eigen::Matrix3d P_imu_vel = state_server.state_cov.block<3, 3>(6, 6);
   717                 Eigen::Matrix3d H_vel = msckf_vio::IMUState::T_imu_body.linear();
   718                 Eigen::Matrix3d P_body_vel = H_vel * P_imu_vel * H_vel.transpose();
   719                 for (
int i = 0; i < 3; ++i)
   720                         for (
int j = 0; j < 3; ++j)
   721                                 odom_msg.twist.covariance[i*6+j] = P_body_vel(i, j);
   727                 feature_msg_ptr.reset(
new pcl::PointCloud<pcl::PointXYZ>());
   728           feature_msg_ptr->header.frame_id = fixed_frame_id;
   729           feature_msg_ptr->height = 1;
   730           for (
const auto& item : map_server) {
   731             const auto& feature = item.second;
   732             if (feature.is_initialized) {
   733               Eigen::Vector3d feature_position =
   734                 msckf_vio::IMUState::T_imu_body.linear() * feature.position;
   735               feature_msg_ptr->points.push_back(pcl::PointXYZ(
   736                     feature_position(0), feature_position(1), feature_position(2)));
   739           feature_msg_ptr->width = feature_msg_ptr->points.size();
   753 #ifdef RTABMAP_MSCKF_VIO
   757 parameters_(parameters),
   758 fixPoseRotation_(0, 0, -1, 0, 0, 1, 0, 0, 1, 0, 0, 0),
   768 #ifdef RTABMAP_MSCKF_VIO   769         delete imageProcessor_;
   777 #ifdef RTABMAP_MSCKF_VIO   782                         delete imageProcessor_;
   791                 previousPose_.setIdentity();
   793         initGravity_ = 
false;
   806 #ifdef RTABMAP_MSCKF_VIO   811                 UDEBUG(
"IMU update stamp=%f acc=%f %f %f gyr=%f %f %f", data.
stamp(),
   818                 if(imageProcessor_ && msckf_)
   820                         sensor_msgs::ImuPtr msg(
new sensor_msgs::Imu);
   827                         msg->header.stamp.fromSec(data.
stamp());
   828                         imageProcessor_->imuCallback(msg);
   829                         msckf_->imuCallback(msg);
   833                         UWARN(
"Ignoring IMU, waiting for an image to initialize...");
   834                         lastImu_ = data.
imu();
   845                                 UINFO(
"Initialization");
   848                                         UWARN(
"Ignoring Image, waiting for imu to initialize...");
   851                                 UINFO(
"Creating ImageProcessorNoROS...");
   852                                 imageProcessor_ = 
new ImageProcessorNoROS(
   854                                                 lastImu_.localTransform(),
   857                                 UINFO(
"Creating MsckfVioNoROS...");
   858                                 msckf_ = 
new MsckfVioNoROS(
   860                                                 lastImu_.localTransform(),
   871                         if(data.
imageRaw().type() == CV_8UC3)
   873                                 cv::cvtColor(data.
imageRaw(), cam0.image, CV_BGR2GRAY);
   879                         if(data.
rightRaw().type() == CV_8UC3)
   888                         sensor_msgs::ImagePtr cam0Msg(
new sensor_msgs::Image);
   889                         sensor_msgs::ImagePtr cam1Msg(
new sensor_msgs::Image);
   890                         cam0.toImageMsg(*cam0Msg);
   895                         msckf_vio::CameraMeasurementPtr measurements = imageProcessor_->stereoCallback2(cam0Msg, cam1Msg);
   896                         pcl::PointCloud<pcl::PointXYZ>::Ptr localMap;
   897                         nav_msgs::Odometry odom = msckf_->featureCallback2(measurements, localMap);
   899                         if( odom.pose.pose.orientation.x != 0.0f ||
   900                                 odom.pose.pose.orientation.y != 0.0f ||
   901                                 odom.pose.pose.orientation.z != 0.0f ||
   902                                 odom.pose.pose.orientation.w != 0.0f)
   905                                                 odom.pose.pose.position.x,
   906                                                 odom.pose.pose.position.y,
   907                                                 odom.pose.pose.position.z,
   908                                                 odom.pose.pose.orientation.x,
   909                                                 odom.pose.pose.orientation.y,
   910                                                 odom.pose.pose.orientation.z,
   911                                                 odom.pose.pose.orientation.w);
   913                                 p = fixPoseRotation_*p;
   921                                 if(previousPose_.isIdentity())
   928                                 t = previousPoseInv*p;
   934                                         info->
features = measurements->features.size();
   937                                         cv::Mat twistCov(6,6,CV_64FC1, odom.twist.covariance.elems);
   940                                         cv::Matx31f covWorldFrame(twistCov.at<
double>(0, 0),
   941                                                                                           twistCov.at<
double>(1, 1),
   942                                                                                           twistCov.at<
double>(2, 2));
   943                                         cv::Matx31f covBaseFrame = cv::Matx33f(previousPoseInv.
rotationMatrix()) * covWorldFrame;
   945                                         info->
reg.
covariance.at<
double>(0, 0) = fabs(covBaseFrame.val[0])/10.0;
   946                                         info->
reg.
covariance.at<
double>(1, 1) = fabs(covBaseFrame.val[1])/10.0;
   947                                         info->
reg.
covariance.at<
double>(2, 2) = fabs(covBaseFrame.val[2])/10.0;
   960                                         info->
reg.
covariance.at<
double>(3, 3) = msckf_vio::IMUState::gyro_noise*10.0;
   966                                                 if(localMap.get() && localMap->size())
   968                                                         Eigen::Affine3f fixRot = fixPoseRotation_.toEigen3f();
   969                                                         for(
unsigned int i=0; i<localMap->size(); ++i)
   972                                                                 info->
localMap.insert(std::make_pair(i, cv::Point3f(pt.x, pt.y, pt.z)));
   977                                                         info->
newCorners.resize(measurements->features.size());
   983                                                         for(
unsigned int i=0; i<measurements->features.size(); ++i)
   985                                                                 info->
newCorners[i].x = measurements->features[i].u0*fx+cx;
   986                                                                 info->
newCorners[i].y = measurements->features[i].v0*fy+cy;
   992                                 UINFO(
"Odom update time = %fs p=%s", timer.
elapsed(), p.prettyPrint().c_str());
   998         UERROR(
"RTAB-Map is not built with MSCKF_VIO support! Select another visual odometry approach.");
 CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
static bool parse(const ParametersMap ¶meters, const std::string &key, bool &value)
bool imagesAlreadyRectified() const
OdometryMSCKF(const rtabmap::ParametersMap ¶meters=rtabmap::ParametersMap())
cv::Point3f RTABMAP_EXP transformPoint(const cv::Point3f &pt, const Transform &transform)
virtual void reset(const Transform &initialPose=Transform::getIdentity())
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
std::map< int, cv::Point3f > localMap
const std::vector< StereoCameraModel > & stereoCameraModels() const
std::map< std::string, std::string > ParametersMap
void swap(linb::any &lhs, linb::any &rhs) noexcept
virtual Odometry::Type getType()
std::vector< int > inliersIDs
#define UASSERT(condition)
Wrappers of STL for convenient functions. 
bool isInfoDataFilled() const
sensor_msgs::ImagePtr toImageMsg() const
const cv::Mat & imageRaw() const
virtual Transform computeTransform(SensorData &image, const Transform &guess=Transform(), OdometryInfo *info=0)
GLM_FUNC_DECL detail::tquat< T, P > rotation(detail::tvec3< T, P > const &orig, detail::tvec3< T, P > const &dest)
GLM_FUNC_DECL bool isIdentity(matType< T, P > const &m, T const &epsilon)
const cv::Vec3d & angularVelocity() const
static const ParametersMap & getDefaultParameters()
ULogger class and convenient macros. 
std::vector< cv::Point2f > newCorners
const cv::Vec3d linearAcceleration() const
virtual void reset(const Transform &initialPose=Transform::getIdentity())
const Transform & getPose() const
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)