39 : params(params_), _db(db) {
42 imu_data = std::make_shared<std::vector<ov_core::ImuData>>();
61 if (oldest_time != -1) {
64 if (it0->timestamp < oldest_time) {
74 std::shared_ptr<ov_type::IMU> t_imu,
bool wait_for_jerk) {
77 double newest_cam_time = -1;
78 for (
auto const &feat :
_db->get_internal_data()) {
79 for (
auto const &camtimepair : feat.second->timestamps) {
80 for (
auto const &time : camtimepair.second) {
81 newest_cam_time = std::max(newest_cam_time, time);
86 if (newest_cam_time < 0 || oldest_time < 0) {
92 _db->cleanup_measurements(oldest_time);
100 bool disparity_detected_moving_1to0 =
false;
101 bool disparity_detected_moving_2to1 =
false;
107 int num_features0 = 0;
108 int num_features1 = 0;
109 double avg_disp0, avg_disp1;
110 double var_disp0, var_disp1;
111 FeatureHelper::compute_disparity(
_db, avg_disp0, var_disp0, num_features0, newest_time_allowed);
112 FeatureHelper::compute_disparity(
_db, avg_disp1, var_disp1, num_features1, newest_cam_time, newest_time_allowed);
115 int feat_thresh = 15;
116 if (num_features0 < feat_thresh || num_features1 < feat_thresh) {
117 PRINT_WARNING(
YELLOW "[init]: not enough feats to compute disp: %d,%d < %d\n" RESET, num_features0, num_features1, feat_thresh);
130 bool has_jerk = (!disparity_detected_moving_1to0 && disparity_detected_moving_2to1);
131 bool is_still = (!disparity_detected_moving_1to0 && !disparity_detected_moving_2to1);
134 return init_static->initialize(timestamp, covariance, order, t_imu, wait_for_jerk);
137 std::map<double, std::shared_ptr<ov_type::PoseJPL>> _clones_IMU;
138 std::unordered_map<size_t, std::shared_ptr<ov_type::Landmark>> _features_SLAM;
139 return init_dynamic->initialize(timestamp, covariance, order, t_imu, _clones_IMU, _features_SLAM);
141 std::string msg = (has_jerk) ?
"" :
"no accel jerk detected";
142 msg += (has_jerk || is_still) ?
"" :
", ";
143 msg += (is_still) ?
"" :
"platform moving too much";