![]() |
Visual Servoing Platform version 3.7.0
|
Classes | |
| class | DisplayType |
Public Member Functions | |
| __init__ (self, XFeatTrackingBackend backend) | |
| bool | requiresRGB (self) |
| bool | requiresDepth (self) |
| bool | requiresSilhouetteCandidates (self) |
| load_settings (self, dict_rep) | |
| onTrackingIterStart (self, RBFeatureTrackerInput frame, HomogeneousMatrix cMo) | |
| extractFeatures (self, RBFeatureTrackerInput frame, RBFeatureTrackerInput previousFrame, HomogeneousMatrix cMo) | |
| trackFeatures (self, RBFeatureTrackerInput frame, RBFeatureTrackerInput previousFrame, HomogeneousMatrix cMo) | |
| initVVS (self, RBFeatureTrackerInput frame, RBFeatureTrackerInput _previousFrame, HomogeneousMatrix _cMo) | |
| computeVVSIter (self, RBFeatureTrackerInput frame, HomogeneousMatrix cMo, int iteration) | |
| onTrackingIterEnd (self, HomogeneousMatrix cMo) | |
| reset (self) | |
| display (self, CameraParameters cam, ImageGray I, ImageRGBa IRGB, ImageGray I_depth) | |
Public Attributes | |
| backend = backend | |
| object_map | |
| idx_curr_obj_matched | |
| idx_object_map_matched = None, None | |
| int | iter = 0 |
| bool | use_3d = False |
| last_cMo = None | |
| robust = Robust() | |
| current_representation = None | |
| display_type = RBXFeatFeatureTracker.DisplayType.SIMPLE | |
| int | numFeatures = 0 |
| removed_indices | |
| frame = frame | |
| list | Zs = [] |
| visp_indices_matched = ArrayInt2D.view(self.idx_object_map_matched[..., None].astype(np.int32)) | |
| current_xy_obj = Matrix.view(np.ascontiguousarray(np.concatenate((xoc[..., None], yoc[..., None]), axis=-1), dtype=np.float64)) | |
| observations = Matrix.view(xyz) | |
| error_per_point = ColVector(self.numFeatures // (2 if not self.use_3d else 3)) | |
| weight_per_point = ColVector(self.error_per_point.getCols()) | |
| L | |
| error | |
| pixel_pos_visible = uvs.numpy().copy() | |
A trackable feature implementation for the RBT that relies on XFeat for keypoint extraction.
XFeat is used to extract keypoints (2D) along with their descriptors in every frame.
At the end of every tracking iteration, Novel keypoints are added in a map (see visp.python.rbt.TrackedDescriptorMap)
Using the 2D keypoint location, the newly computed 3D camera pose and the render information
This feature relies on the XFeat tracker backend,
which should be customized to set the number of keypoints to retrieve each frame along with the minimum similarity score for the matching step.
The error that is computed is either the reprojection error (2D, in normalized image plane coordinates, similar to an IBVS)
or in 3D (in metric space) if the option is chosen and an RGB-D camera is used.
An example JSON configuration of the tracker is:
{
"type": "xfeat",
"weight": 1,
"use_3d": false,
"display": true,
"numPoints": 4096,
"reprojectionThreshold": 5,
"minDistNewPoint": 0.0,
"maxDepthErrorVisible": 0.02,
"maxDepthErrorCandidate": 0.02
}
See the TrackedDescriptorMap class for some of the settings description.
Definition at line 51 of file RBXFeatFeatureTracker.py.
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.__init__ | ( | self, | |
| XFeatTrackingBackend | backend ) |
Definition at line 87 of file RBXFeatFeatureTracker.py.
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.computeVVSIter | ( | self, | |
| RBFeatureTrackerInput | frame, | ||
| HomogeneousMatrix | cMo, | ||
| int | iteration ) |
Definition at line 200 of file RBXFeatFeatureTracker.py.
References numFeatures, and use_3d.
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.display | ( | self, | |
| CameraParameters | cam, | ||
| ImageGray | I, | ||
| ImageRGBa | IRGB, | ||
| ImageGray | I_depth ) |
Definition at line 259 of file RBXFeatFeatureTracker.py.
References current_representation, display_type, idx_curr_obj_matched, numFeatures, object_map, pixel_pos_visible, and vpNurbs.weights.
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.extractFeatures | ( | self, | |
| RBFeatureTrackerInput | frame, | ||
| RBFeatureTrackerInput | previousFrame, | ||
| HomogeneousMatrix | cMo ) |
Definition at line 134 of file RBXFeatFeatureTracker.py.
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.initVVS | ( | self, | |
| RBFeatureTrackerInput | frame, | ||
| RBFeatureTrackerInput | _previousFrame, | ||
| HomogeneousMatrix | _cMo ) |
Definition at line 178 of file RBXFeatFeatureTracker.py.
References error, idx_object_map_matched, L, numFeatures, and vpNurbs.weights.
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.load_settings | ( | self, | |
| dict_rep ) |
Definition at line 111 of file RBXFeatFeatureTracker.py.
References object_map, vpRBFeatureTracker.setFeaturesShouldBeDisplayed(), vpRBFeatureTracker.setTrackerWeight(), vpRBFeatureTracker.setTrackerWeight(), and use_3d.
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.onTrackingIterEnd | ( | self, | |
| HomogeneousMatrix | cMo ) |
Definition at line 236 of file RBXFeatFeatureTracker.py.
References frame, idx_curr_obj_matched, idx_object_map_matched, numFeatures, and object_map.
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.onTrackingIterStart | ( | self, | |
| RBFeatureTrackerInput | frame, | ||
| HomogeneousMatrix | cMo ) |
Definition at line 118 of file RBXFeatFeatureTracker.py.
| bool visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.requiresDepth | ( | self | ) |
Definition at line 106 of file RBXFeatFeatureTracker.py.
References use_3d.
| bool visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.requiresRGB | ( | self | ) |
Definition at line 104 of file RBXFeatFeatureTracker.py.
| bool visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.requiresSilhouetteCandidates | ( | self | ) |
Definition at line 108 of file RBXFeatFeatureTracker.py.
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.reset | ( | self | ) |
Definition at line 249 of file RBXFeatFeatureTracker.py.
References current_representation, current_xy_obj, frame, idx_curr_obj_matched, idx_object_map_matched, iter, vpKalmanFilter.iter, numFeatures, object_map, and reset().
Referenced by reset().
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.trackFeatures | ( | self, | |
| RBFeatureTrackerInput | frame, | ||
| RBFeatureTrackerInput | previousFrame, | ||
| HomogeneousMatrix | cMo ) |
Definition at line 138 of file RBXFeatFeatureTracker.py.
References backend, current_representation, idx_curr_obj_matched, idx_object_map_matched, numFeatures, object_map, and use_3d.
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.backend = backend |
Definition at line 90 of file RBXFeatFeatureTracker.py.
Referenced by visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.compute(), and trackFeatures().
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.current_representation = None |
Definition at line 100 of file RBXFeatFeatureTracker.py.
Referenced by visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.compute(), display(), visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.display(), reset(), visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.reset(), and trackFeatures().
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.current_xy_obj = Matrix.view(np.ascontiguousarray(np.concatenate((xoc[..., None], yoc[..., None]), axis=-1), dtype=np.float64)) |
Definition at line 190 of file RBXFeatFeatureTracker.py.
Referenced by reset().
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.display_type = RBXFeatFeatureTracker.DisplayType.SIMPLE |
Definition at line 101 of file RBXFeatFeatureTracker.py.
Referenced by display(), visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.display(), and visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.load_settings().
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.error |
Definition at line 207 of file RBXFeatFeatureTracker.py.
Referenced by yolo-centering-task-afma6.VSPlot.generate_anim(), yolo-centering-task.VSPlot.generate_anim(), initVVS(), yolo-centering-task-afma6.VSPlot.on_iter(), yolo-centering-task.VSPlot.on_iter(), and visp.python.rbt.xfeat.XFeatPoseEstimator.XFeatViewPointPoseEstimator.ViewPointMatcher.optimize_2d().
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.error_per_point = ColVector(self.numFeatures // (2 if not self.use_3d else 3)) |
Definition at line 197 of file RBXFeatFeatureTracker.py.
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.frame = frame |
Definition at line 135 of file RBXFeatFeatureTracker.py.
Referenced by onTrackingIterEnd(), and reset().
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.idx_curr_obj_matched |
Definition at line 95 of file RBXFeatFeatureTracker.py.
Referenced by display(), onTrackingIterEnd(), reset(), and trackFeatures().
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.idx_object_map_matched = None, None |
Definition at line 95 of file RBXFeatFeatureTracker.py.
Referenced by initVVS(), onTrackingIterEnd(), reset(), and trackFeatures().
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.iter = 0 |
Definition at line 96 of file RBXFeatFeatureTracker.py.
Referenced by visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.compute(), reset(), and visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.reset().
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.L |
Definition at line 207 of file RBXFeatFeatureTracker.py.
Referenced by initVVS().
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.last_cMo = None |
Definition at line 98 of file RBXFeatFeatureTracker.py.
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.numFeatures = 0 |
Definition at line 122 of file RBXFeatFeatureTracker.py.
Referenced by computeVVSIter(), display(), initVVS(), onTrackingIterEnd(), reset(), and trackFeatures().
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.object_map |
Definition at line 91 of file RBXFeatFeatureTracker.py.
Referenced by display(), load_settings(), onTrackingIterEnd(), reset(), and trackFeatures().
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.observations = Matrix.view(xyz) |
Definition at line 193 of file RBXFeatFeatureTracker.py.
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.pixel_pos_visible = uvs.numpy().copy() |
Definition at line 243 of file RBXFeatFeatureTracker.py.
Referenced by display().
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.removed_indices |
Definition at line 125 of file RBXFeatFeatureTracker.py.
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.robust = Robust() |
Definition at line 99 of file RBXFeatFeatureTracker.py.
| bool visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.use_3d = False |
Definition at line 97 of file RBXFeatFeatureTracker.py.
Referenced by computeVVSIter(), visp.python.rbt.xfeat.XFeatPoseEstimator.XFeatViewPointPoseEstimator.estimate_pose(), load_settings(), visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.load_settings(), requiresDepth(), and trackFeatures().
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.visp_indices_matched = ArrayInt2D.view(self.idx_object_map_matched[..., None].astype(np.int32)) |
Definition at line 186 of file RBXFeatFeatureTracker.py.
| visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.weight_per_point = ColVector(self.error_per_point.getCols()) |
Definition at line 198 of file RBXFeatFeatureTracker.py.
| list visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.Zs = [] |
Definition at line 165 of file RBXFeatFeatureTracker.py.