예제 #1
0
 def updateHistory(self):
     if (self.init_history is True) and (self.trueX is not None):
         self.t0_est = np.array([self.cur_t[0], self.cur_t[1], self.cur_t[2]])  # starting translation 
         self.t0_gt  = np.array([self.trueX, self.trueY, self.trueZ])           # starting translation 
         self.init_history = False 
     if (self.t0_est is not None) and (self.t0_gt is not None):             
         p = [self.cur_t[0]-self.t0_est[0], self.cur_t[1]-self.t0_est[1], self.cur_t[2]-self.t0_est[2]]   # the estimated traj starts at 0
         self.traj3d_est.append(p)
         pg = [self.trueX-self.t0_gt[0], self.trueY-self.t0_gt[1], self.trueZ-self.t0_gt[2]]  # the groudtruth traj starts at 0  
         self.traj3d_gt.append(pg)     
         self.poses.append(poseRt(self.cur_R, p))   
예제 #2
0
 def estimate_pose_ess_mat(self, kpn_ref, kpn_cur):
     E, self.mask_match = cv2.findEssentialMat(
         kpn_cur,
         kpn_ref,
         focal=1,
         pp=(0., 0.),
         method=cv2.RANSAC,
         prob=kRansacProb,
         threshold=kRansacThresholdNormalized)
     _, R, t, mask = cv2.recoverPose(E,
                                     kpn_cur,
                                     kpn_ref,
                                     focal=1,
                                     pp=(0., 0.))
     return poseRt(R, t.T)  # Rrc,trc (cur with respect to 'ref' frame)
예제 #3
0
 def updateHistory(self):
     f_cur = self.map.frames[-1]
     self.cur_R = f_cur.pose[:3, :3].T
     self.cur_t = np.dot(-self.cur_R, f_cur.pose[:3, 3])
     if (self.init_history is True) and (self.trueX is not None):
         self.t0_est = np.array(
             [self.cur_t[0], self.cur_t[1],
              self.cur_t[2]])  # starting translation
         self.t0_gt = np.array([self.trueX, self.trueY,
                                self.trueZ])  # starting translation
     if (self.t0_est is not None) and (self.t0_gt is not None):
         p = [
             self.cur_t[0] - self.t0_est[0], self.cur_t[1] - self.t0_est[1],
             self.cur_t[2] - self.t0_est[2]
         ]  # the estimated traj starts at 0
         self.traj3d_est.append(p)
         self.traj3d_gt.append([
             self.trueX - self.t0_gt[0], self.trueY - self.t0_gt[1],
             self.trueZ - self.t0_gt[2]
         ])
         self.poses.append(poseRt(self.cur_R, p))
예제 #4
0
    def track(self, img, frame_id, pose=None, verts=None):
        # check image size is coherent with camera params
        print("img.shape ", img.shape)
        print("cam ", self.H, " x ", self.W)
        assert img.shape[0:2] == (self.H, self.W)

        self.timer_main_track.start()

        # build current frame
        self.timer_frame.start()
        f_cur = Frame(self.map, img, self.K, self.Kinv, self.D, des=verts)
        self.timer_frame.refresh()

        if self.stage == SLAMStage.NO_IMAGES_YET:
            # push first frame in the inizializer
            self.intializer.init(f_cur)
            self.stage = SLAMStage.NOT_INITIALIZED
            return  # EXIT (jump to second frame)

        if self.stage == SLAMStage.NOT_INITIALIZED:
            # try to inizialize
            initializer_output, is_ok = self.intializer.initialize(f_cur, img)
            if is_ok:
                f_ref = self.intializer.f_ref
                # add the two initialized frames in the map
                self.map.add_frame(
                    f_ref)  # add first frame in map and update its id
                self.map.add_frame(
                    f_cur)  # add second frame in map and update its id
                # add points in map
                new_pts_count, _ = self.map.add_points(
                    initializer_output.points4d, None, f_cur, f_ref,
                    initializer_output.idx_cur, initializer_output.idx_ref,
                    img)
                Printer.green("map: initialized %d new points" %
                              (new_pts_count))
                self.stage = SLAMStage.OK
            return  # EXIT (jump to next frame)

        f_ref = self.map.frames[-1]  # get previous frame in map
        self.map.add_frame(f_cur)  # add f_cur to map

        # udpdate (velocity) motion model (kinematic without damping)
        self.velocity = np.dot(f_ref.pose,
                               np.linalg.inv(self.map.frames[-2].pose))
        predicted_pose = np.dot(self.velocity, f_ref.pose)

        if kUseMotionModel is True:
            print('using motion model')
            # set intial guess for current pose optimization
            f_cur.pose = predicted_pose.copy()
            #f_cur.pose = f_ref.pose.copy()  # get the last pose as an initial guess for optimization

            if kUseSearchFrameByProjection:
                # search frame by projection: match map points observed in f_ref with keypoints of f_cur
                print('search frame by projection...')
                idx_ref, idx_cur, num_found_map_pts = search_frame_by_projection(
                    f_ref, f_cur)
                print("# found map points in prev frame: %d " %
                      num_found_map_pts)
            else:
                self.timer_match.start()
                # find keypoint matches between f_cur and f_ref
                idx_cur, idx_ref = match_frames(f_cur, f_ref)
                self.num_matched_kps = idx_cur.shape[0]
                print('# keypoint matches: ', self.num_matched_kps)
                self.timer_match.refresh()

        else:
            print('estimating pose by fitting essential mat')

            self.timer_match.start()
            # find keypoint matches between f_cur and f_ref
            idx_cur, idx_ref = match_frames(f_cur, f_ref)
            self.num_matched_kps = idx_cur.shape[0]
            print('# keypoint matches: ', self.num_matched_kps)
            self.timer_match.refresh()

            # N.B.: please, in order to understand the limitations of fitting an essential mat, read the comments of the method self.estimate_pose_ess_mat()
            self.timer_pose_est.start()
            # estimate inter frame camera motion by using found keypoint matches
            Mrc = self.estimate_pose_ess_mat(f_ref.kpsn[idx_ref],
                                             f_cur.kpsn[idx_cur])
            Mcr = np.linalg.inv(poseRt(Mrc[:3, :3], Mrc[:3, 3]))
            f_cur.pose = np.dot(Mcr, f_ref.pose)
            self.timer_pose_est.refresh()

            # remove outliers from keypoint matches by using the mask computed with inter frame pose estimation
            mask_index = (self.mask_match.ravel() == 1)
            self.num_inliers = sum(mask_index)
            print('# inliers: ', self.num_inliers)
            idx_ref = idx_ref[mask_index]
            idx_cur = idx_cur[mask_index]

            # if too many outliers reset estimated pose
            if self.num_inliers < kNumMinInliersEssentialMat:
                f_cur.pose = f_ref.pose.copy(
                )  # reset estimated pose to previous frame
                Printer.red('Essential mat: not enough inliers!')

            # set intial guess for current pose optimization:
            # keep the estimated rotation and override translation with ref frame translation (we do not have a proper scale for the translation)
            f_cur.pose[:, 3] = f_ref.pose[:, 3].copy()
            #f_cur.pose[:,3] = predicted_pose[:,3].copy()  # or use motion model for translation

        # populate f_cur with map points by propagating map point matches of f_ref:
        # we use map points observed in f_ref and keypoint matches between f_ref and f_cur
        num_found_map_pts_inter_frame = 0
        if not kUseSearchFrameByProjection:
            for i, idx in enumerate(idx_ref):  # iterate over keypoint matches
                if f_ref.points[
                        idx] is not None:  # if we have a map point P for i-th matched keypoint in f_ref
                    f_ref.points[idx].add_observation(
                        f_cur, idx_cur[i]
                    )  # then P is automatically matched to the i-th matched keypoint in f_cur
                    num_found_map_pts_inter_frame += 1
            print("# matched map points in prev frame: %d " %
                  num_found_map_pts_inter_frame)

        # f_cur pose optimization 1  (here we use first available information coming from first guess of f_cur pose and map points of f_ref matched keypoints )
        self.timer_pose_opt.start()
        pose_opt_error, pose_is_ok, self.num_vo_map_points = optimizer_g2o.poseOptimization(
            f_cur, verbose=False)
        print("pose opt err1: %f,  ok: %d" % (pose_opt_error, int(pose_is_ok)))
        # discard outliers detected in pose optimization (in current frame)
        #f_cur.reset_outlier_map_points()

        if pose_is_ok is True:
            # discard outliers detected in f_cur pose optimization (in current frame)
            f_cur.reset_outlier_map_points()
        else:
            # if current pose optimization failed, reset f_cur pose to f_ref pose
            f_cur.pose = f_ref.pose.copy()

        self.timer_pose_opt.pause()

        # TODO: add recover in case of f_cur pose optimization failure

        # now, having a better estimate of f_cur pose, we can find more map point matches:
        # find matches between {local map points} (points in the built local map) and {unmatched keypoints of f_cur}
        if pose_is_ok is True and not self.map.local_map.is_empty():
            self.timer_seach_map.start()
            #num_found_map_pts = search_local_frames_by_projection(self.map, f_cur)
            num_found_map_pts = search_map_by_projection(
                self.map.local_map.points, f_cur)  # use the built local map
            print("# matched map points in local map: %d " % num_found_map_pts)
            self.timer_seach_map.refresh()

            # f_cur pose optimization 2 with all the matched map points
            self.timer_pose_opt.resume()
            pose_opt_error, pose_is_ok, self.num_vo_map_points = optimizer_g2o.poseOptimization(
                f_cur, verbose=False)
            print("pose opt err2: %f,  ok: %d" %
                  (pose_opt_error, int(pose_is_ok)))
            print("# valid matched map points: %d " % self.num_vo_map_points)
            # discard outliers detected in pose optimization (in current frame)
            if pose_is_ok is True:
                f_cur.reset_outlier_map_points()
            self.timer_pose_opt.refresh()

        if kUseSearchFrameByProjection:
            print("search for triangulation with epipolar lines...")
            idx_ref, idx_cur, self.num_matched_kps, _ = search_frame_for_triangulation(
                f_ref, f_cur, img)
            print("# matched keypoints in prev frame: %d " %
                  self.num_matched_kps)

        # if pose is ok, then we try to triangulate the matched keypoints (between f_cur and f_ref) that do not have a corresponding map point
        if pose_is_ok is True and len(idx_ref) > 0:
            self.timer_triangulation.start()

            # TODO: this triangulation should be done from keyframes!
            good_pts4d = np.array([
                f_cur.points[i] is None for i in idx_cur
            ])  # matched keypoints of f_cur without a corresponding map point
            # do triangulation in global frame
            pts4d = triangulate_points(f_cur.pose, f_ref.pose,
                                       f_cur.kpsn[idx_cur],
                                       f_ref.kpsn[idx_ref], good_pts4d)
            good_pts4d &= np.abs(pts4d[:, 3]) != 0
            #pts4d /= pts4d[:, 3:]
            pts4d[good_pts4d] /= pts4d[good_pts4d,
                                       3:]  # get homogeneous 3-D coords

            new_pts_count, _ = self.map.add_points(pts4d,
                                                   good_pts4d,
                                                   f_cur,
                                                   f_ref,
                                                   idx_cur,
                                                   idx_ref,
                                                   img,
                                                   check_parallax=True)
            print("# added map points: %d " % (new_pts_count))
            self.timer_triangulation.refresh()

        # local optimization
        self.time_local_opt.start()
        err = self.map.locally_optimize(local_window=kLocalWindow)
        print("local optimization error:   %f" % err)
        self.time_local_opt.refresh()

        # large window optimization of the map
        # TODO: move this in a seperate thread with local mapping
        if kUseLargeWindowBA is True and f_cur.id >= parameters.kEveryNumFramesLargeWindowBA and f_cur.id % parameters.kEveryNumFramesLargeWindowBA == 0:
            err = self.map.optimize(
                local_window=parameters.kLargeWindow)  # verbose=True)
            Printer.blue("large window optimization error:   %f" % err)

        print("map: %d points, %d frames" %
              (len(self.map.points), len(self.map.frames)))
        #self.updateHistory()

        self.timer_main_track.refresh()
예제 #5
0
def optimization(frames,
                 points,
                 local_window,
                 fixed_points=False,
                 verbose=False,
                 rounds=40,
                 use_robust_kernel=False):
    if local_window is None:
        local_frames = frames
    else:
        local_frames = frames[-local_window:]

    # create g2o optimizer
    opt = g2o.SparseOptimizer()
    solver = g2o.BlockSolverSE3(g2o.LinearSolverCSparseSE3())
    solver = g2o.OptimizationAlgorithmLevenberg(solver)
    opt.set_algorithm(solver)

    thHuberMono = math.sqrt(5.991)
    # chi-square 2 DOFS

    graph_frames, graph_points = {}, {}

    # add frame vertices to graph
    for f in (
            local_frames if fixed_points else frames
    ):  # if points are fixed then consider just the local frames, otherwise we need all frames or at least two frames for each point
        #print('adding vertex frame ', f.id, ' to graph')
        pose = f.pose
        se3 = g2o.SE3Quat(pose[0:3, 0:3], pose[0:3, 3])
        v_se3 = g2o.VertexSE3Expmap()
        v_se3.set_estimate(se3)
        v_se3.set_id(f.id * 2)  # even ids
        v_se3.set_fixed(f.id < 1 or f not in local_frames)
        opt.add_vertex(v_se3)

        # confirm pose correctness
        #est = v_se3.estimate()
        #assert np.allclose(pose[0:3, 0:3], est.rotation().matrix())
        #assert np.allclose(pose[0:3, 3], est.translation())

        graph_frames[f] = v_se3

    # add point vertices to graph
    for p in points:
        if p.is_bad and not fixed_points:
            continue
        if not any([f in local_frames for f in p.frames]):
            continue
        #print('adding vertex point ', p.id,' to graph')
        v_p = g2o.VertexSBAPointXYZ()
        v_p.set_id(p.id * 2 + 1)  # odd ids
        v_p.set_estimate(p.pt[0:3])
        v_p.set_marginalized(True)
        v_p.set_fixed(fixed_points)
        opt.add_vertex(v_p)
        graph_points[p] = v_p

        # add edges
        for f, idx in zip(p.frames, p.idxs):
            if f not in graph_frames:
                continue
            #print('adding edge between point ', p.id,' and frame ', f.id)
            edge = g2o.EdgeSE3ProjectXYZ()
            edge.set_vertex(0, v_p)
            edge.set_vertex(1, graph_frames[f])
            edge.set_measurement(f.kpsu[idx])
            invSigma2 = Frame.detector.inv_level_sigmas2[f.octaves[idx]]
            edge.set_information(np.eye(2) * invSigma2)
            if use_robust_kernel:
                edge.set_robust_kernel(g2o.RobustKernelHuber(thHuberMono))

            edge.fx = f.fx
            edge.fy = f.fy
            edge.cx = f.cx
            edge.cy = f.cy

            opt.add_edge(edge)

    if verbose:
        opt.set_verbose(True)
    opt.initialize_optimization()
    opt.optimize(rounds)

    # put frames back
    for f in graph_frames:
        est = graph_frames[f].estimate()
        R = est.rotation().matrix()
        t = est.translation()
        f.pose = poseRt(R, t)

    # put points back
    if not fixed_points:
        for p in graph_points:
            p.pt = np.array(graph_points[p].estimate())

    return opt.active_chi2()
예제 #6
0
def localOptimization(frames,
                      points,
                      frames_ref=[],
                      fixed_points=False,
                      verbose=False,
                      rounds=10):

    # create g2o optimizer
    opt = g2o.SparseOptimizer()
    solver = g2o.BlockSolverSE3(g2o.LinearSolverCSparseSE3())
    solver = g2o.OptimizationAlgorithmLevenberg(solver)
    opt.set_algorithm(solver)

    #robust_kernel = g2o.RobustKernelHuber(np.sqrt(5.991))  # chi-square 2 DOFs
    thHuberMono = math.sqrt(5.991)
    # chi-square 2 DOFS

    graph_frames, graph_points = {}, {}

    all_frames = frames + frames_ref

    # add frame vertices to graph
    for f in all_frames:
        #print('adding vertex frame ', f.id, ' to graph')
        pose = f.pose
        se3 = g2o.SE3Quat(pose[0:3, 0:3], pose[0:3, 3])
        v_se3 = g2o.VertexSE3Expmap()
        v_se3.set_estimate(se3)
        v_se3.set_id(f.id * 2)  # even ids
        v_se3.set_fixed(f.id < 1 or f in frames_ref)
        opt.add_vertex(v_se3)
        graph_frames[f] = v_se3
        # confirm pose correctness
        #est = v_se3.estimate()
        #assert np.allclose(pose[0:3, 0:3], est.rotation().matrix())
        #assert np.allclose(pose[0:3, 3], est.translation())

    graph_edges = {}
    num_point_edges = 0

    # add point vertices to graph
    for p in points:
        assert (p is not None)
        if p.is_bad and not fixed_points:  # do not consider bad points unless they are fixed
            continue
        if not any([f in frames for f in p.frames]):  # this is redundant now
            continue
        #print('adding vertex point ', p.id,' to graph')
        v_p = g2o.VertexSBAPointXYZ()
        v_p.set_id(p.id * 2 + 1)  # odd ids
        v_p.set_estimate(p.pt[0:3])
        v_p.set_marginalized(True)
        v_p.set_fixed(fixed_points)
        opt.add_vertex(v_p)
        graph_points[p] = v_p

        # add edges
        for f, p_idx in zip(p.frames, p.idxs):
            assert (f.points[p_idx] == p)
            if f not in graph_frames:
                continue
            #print('adding edge between point ', p.id,' and frame ', f.id)
            edge = g2o.EdgeSE3ProjectXYZ()
            edge.set_vertex(0, v_p)
            edge.set_vertex(1, graph_frames[f])
            edge.set_measurement(f.kpsu[p_idx])
            invSigma2 = Frame.detector.inv_level_sigmas2[f.octaves[p_idx]]
            edge.set_information(np.eye(2) * invSigma2)
            edge.set_robust_kernel(g2o.RobustKernelHuber(thHuberMono))

            edge.fx = f.fx
            edge.fy = f.fy
            edge.cx = f.cx
            edge.cy = f.cy

            opt.add_edge(edge)

            graph_edges[edge] = (p, f, p_idx)  # f.points[p_idx] == p
            num_point_edges += 1

    if verbose:
        opt.set_verbose(True)

    # initial optimization
    opt.initialize_optimization()
    opt.optimize(5)

    chi2Mono = 5.991  # chi-square 2 DOFs

    # check inliers observation
    for edge, edge_data in graph_edges.items():
        p = edge_data[0]
        if p.is_bad is True:
            continue
        if edge.chi2() > chi2Mono or not edge.is_depth_positive():
            edge.set_level(1)
        edge.set_robust_kernel(None)

    # optimize again without outliers
    opt.initialize_optimization()
    opt.optimize(rounds)

    # clean map observations
    num_bad_observations = 0
    outliers_data = []
    for edge, edge_data in graph_edges.items():
        p, f, p_idx = edge_data
        if p.is_bad is True:
            continue
        assert (f.points[p_idx] == p)
        if edge.chi2() > chi2Mono or not edge.is_depth_positive():
            num_bad_observations += 1
            outliers_data.append((p, f, p_idx))

    for d in outliers_data:
        (p, f, p_idx) = d
        assert (f.points[p_idx] == p)
        p.remove_observation(f, p_idx)
        f.remove_point(p)

    # put frames back
    for f in graph_frames:
        est = graph_frames[f].estimate()
        R = est.rotation().matrix()
        t = est.translation()
        f.pose = poseRt(R, t)

    # put points back
    if not fixed_points:
        for p in graph_points:
            p.pt = np.array(graph_points[p].estimate())

    return opt.active_chi2(), num_bad_observations / num_point_edges
예제 #7
0
def poseOptimization(frame, verbose=False, rounds=10):

    is_ok = True

    # create g2o optimizer
    opt = g2o.SparseOptimizer()
    solver = g2o.BlockSolverSE3(g2o.LinearSolverCSparseSE3())
    solver = g2o.OptimizationAlgorithmLevenberg(solver)
    opt.set_algorithm(solver)

    #robust_kernel = g2o.RobustKernelHuber(np.sqrt(5.991))  # chi-square 2 DOFs
    thHuberMono = math.sqrt(5.991)
    # chi-square 2 DOFS

    point_edge_pairs = {}
    num_point_edges = 0

    se3 = g2o.SE3Quat(frame.pose[0:3, 0:3], frame.pose[0:3, 3])
    v_se3 = g2o.VertexSE3Expmap()
    v_se3.set_estimate(se3)
    v_se3.set_id(0)
    v_se3.set_fixed(False)
    opt.add_vertex(v_se3)

    # add point vertices to graph
    for idx, p in enumerate(frame.points):
        if p is None:  # do not use p.is_bad here since a single point observation is ok for pose optimization
            continue

        frame.outliers[idx] = False

        # add edge
        #print('adding edge between point ', p.id,' and frame ', frame.id)
        edge = g2o.EdgeSE3ProjectXYZOnlyPose()

        edge.set_vertex(0, opt.vertex(0))
        edge.set_measurement(frame.kpsu[idx])
        invSigma2 = Frame.detector.inv_level_sigmas2[frame.octaves[idx]]
        edge.set_information(np.eye(2) * invSigma2)
        edge.set_robust_kernel(g2o.RobustKernelHuber(thHuberMono))

        edge.fx = frame.fx
        edge.fy = frame.fy
        edge.cx = frame.cx
        edge.cy = frame.cy
        edge.Xw = p.pt[0:3]

        opt.add_edge(edge)

        point_edge_pairs[p] = (edge, idx)  # one edge per point
        num_point_edges += 1

    if num_point_edges < 3:
        Printer.red('poseOptimization: not enough correspondences!')
        is_ok = False
        return 0, is_ok, 0

    if verbose:
        opt.set_verbose(True)

    # We perform 4 optimizations, after each optimization we classify observation as inlier/outlier
    # At the next optimization, outliers are not included, but at the end they can be classified as inliers again.
    chi2Mono = 5.991  # chi-square 2 DOFs
    num_bad_points = 0

    for it in range(4):
        opt.initialize_optimization()
        opt.optimize(rounds)

        num_bad_points = 0

        for p, edge_pair in point_edge_pairs.items():
            if frame.outliers[edge_pair[1]] is True:
                edge_pair[0].compute_error()

            chi2 = edge_pair[0].chi2()
            if chi2 > chi2Mono:
                frame.outliers[edge_pair[1]] = True
                edge_pair[0].set_level(1)
                num_bad_points += 1
            else:
                frame.outliers[edge_pair[1]] = False
                edge_pair[0].set_level(0)

            if it == 2:
                edge_pair[0].set_robust_kernel(None)

        if len(opt.edges()) < 10:
            Printer.red('poseOptimization: stopped - not enough edges!')
            is_ok = False
            break

    print('pose optimization: initial ', num_point_edges, ' points, found ',
          num_bad_points, ' bad points')
    if num_point_edges == num_bad_points:
        Printer.red(
            'poseOptimization: all the initial correspondences are bad!')
        is_ok = False

    # update pose estimation
    if is_ok is True:
        est = v_se3.estimate()
        R = est.rotation().matrix()
        t = est.translation()
        frame.pose = poseRt(R, t)

    num_valid_points = num_point_edges - num_bad_points

    return opt.active_chi2(), is_ok, num_valid_points
예제 #8
0
    def initialize(self, f_cur, img_cur):

        # prepare the output
        out = InitializerOutput()
        is_ok = False

        # if too many frames have passed, move the current id_ref forward
        if (len(self.frames) - 1) - self.id_ref >= kMaxIdDistBetweenFrames:
            self.id_ref = len(self.frames) - 1  # take last frame in the array
        self.f_ref = self.frames[self.id_ref]
        f_ref = self.f_ref

        # append current frame
        self.frames.append(f_cur)

        # if the current frames do no have enough features exit
        if len(f_ref.kps) < kNumMinFeatures or len(
                f_cur.kps) < kNumMinFeatures:
            Printer.red('Inializer: not enough features!')
            return out, is_ok

        # find image point matches
        idx_cur, idx_ref = match_frames(f_cur, f_ref)

        print('├────────')
        print('initializing frames ', f_cur.id, ', ', f_ref.id)
        Mrc = self.estimatePose(f_ref.kpsn[idx_ref], f_cur.kpsn[idx_cur])
        f_cur.pose = np.linalg.inv(poseRt(
            Mrc[:3, :3], Mrc[:3, 3]))  # [Rcr, tcr] w.r.t. ref frame

        # remove outliers
        mask_index = [i for i, v in enumerate(self.mask_match) if v > 0]
        print('num inliers: ', len(mask_index))
        idx_cur_inliers = idx_cur[mask_index]
        idx_ref_inliers = idx_ref[mask_index]

        # create a temp map for initializing
        map = Map()
        map.add_frame(f_ref)
        map.add_frame(f_cur)

        points4d = self.triangulatePoints(f_cur.pose, f_ref.pose,
                                          f_cur.kpsn[idx_cur_inliers],
                                          f_ref.kpsn[idx_ref_inliers])
        #pts4d = triangulate(f_cur.pose, f_ref.pose, f_cur.kpsn[idx_cur], f_ref.kpsn[idx_ref])

        new_pts_count, mask_points = map.add_points(points4d,
                                                    None,
                                                    f_cur,
                                                    f_ref,
                                                    idx_cur_inliers,
                                                    idx_ref_inliers,
                                                    img_cur,
                                                    check_parallax=True)
        print("triangulated:      %d new points from %d matches" %
              (new_pts_count, len(idx_cur)))
        err = map.optimize(verbose=False)
        print("pose opt err:   %f" % err)

        #reset points in frames
        f_cur.reset_points()
        f_ref.reset_points()

        num_map_points = len(map.points)
        #print("# map points:   %d" % num_map_points)
        is_ok = num_map_points > kNumMinTriangulatedPoints

        out.points4d = points4d[mask_points]
        out.f_cur = f_cur
        out.idx_cur = idx_cur_inliers[mask_points]
        out.f_ref = f_ref
        out.idx_ref = idx_ref_inliers[mask_points]

        # set median depth to 'desired_median_depth'
        desired_median_depth = parameters.kInitializerDesiredMedianDepth
        median_depth = f_cur.compute_points_median_depth(out.points4d)
        depth_scale = desired_median_depth / median_depth
        print('median depth: ', median_depth)

        out.points4d = out.points4d * depth_scale  # scale points
        f_cur.pose[:3,
                   3] = f_cur.pose[:3,
                                   3] * depth_scale  # scale initial baseline

        print('├────────')
        Printer.green('Inializer: ok!')
        return out, is_ok