Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry Class Reference
Inheritance diagram for visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry:

Classes

class  DisplayType

Public Member Functions

 __init__ (self, XFeatTrackingBackend backend)
 compute_weights (self, torch.Tensor obj_descriptors)
 load_settings (self, d)
None compute (self, RBFeatureTrackerInput frame, RBFeatureTrackerInput previousFrame)
 optimize (self, RBFeatureTrackerInput frame)
 reset (self)
HomogeneousMatrix getCameraMotion (self)
HomogeneousMatrix getCameraPose (self)
 display (self, CameraParameters cam, ImageGray _I, ImageRGBa IRGB, ImageGray _I_depth)

Public Attributes

 backend = backend
 environment_map
 display_type = XFeatVisualOdometry.DisplayType.SIMPLE
bool use_3d = False
 current_representation = None
 idx_curr_env_matched
 idx_environment_map = None, None
int iter = 0
 cTw = HomogeneousMatrix()
 cnTc = None
 optim_params = LevenbergMarquardtParameters()
int numFeatures = 0
list Zs = []
 previous_cTw = HomogeneousMatrix(self.cTw)

Detailed Description

Visual odometry implementation based on XFeat keypoints.
The minimised error is either the reprojection or the 3D error (in meters)
Descriptors are associated to 3D points that are stored in a map.
This map is updated every iteration, with mismatched points being removed and novel keypoints being added.

Every iteration, keypoints in the current RGB frame that are matched with points in the map are used to
update the camera pose by minimizing the chosen error criterion.

This implementation requires an RGB-D camera to compute the actual 3D positions of newly detected keypoints.

The parameters are the following:
- "numPoints" Number of points to store in the map
- "reprojectionThreshold": Distance (in pixels) between observed keypoints and model keypoints above which a map point is considered an outlier and is removed.
- "minDistNewPoint": Minimum distance (in meters) that a new keypoints should have to all other keypoints to be added to the map. This can help ensure that there is no overlapping keypoints in a region.
- "maxDepthErrorVisible": Maximum depth error between 3D map point and observed depth value (from the camera) above which a point is considered as not visible (occluded)

- "gain": The optimizer gain
- "maxNumIters": Maximum number of optimizer iterations
- "muInit": Initial value of the Levenberg-Marquardt regularization parameter
- "muIterFactor": LM regularization scaling factor applied every iteration
- "minImprovementFactor": Improvement factor (expressed as a ratio of the previous to current error criterion values) below which optimization is stopped.


An example JSON representation of the available settings is:
{
  "type": "xfeat",
  "numPoints": 8192,
  "reprojectionThreshold": 10.0,
  "minDistNewPoint": 0.0,
  "maxDepthErrorVisible": 0.02,

  "maxDepthErrorCandidate": 0.0,

  "gain": 0.5,
  "maxNumIters": 10,
  "muInit": 0.0,
  "muIterFactor": 0.0,
  "minImprovementFactor": 0.001
}

Definition at line 50 of file XFeatVisualOdometry.py.

Constructor & Destructor Documentation

◆ __init__()

visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.__init__ ( self,
XFeatTrackingBackend backend )

Definition at line 102 of file XFeatVisualOdometry.py.

Member Function Documentation

◆ compute()

◆ compute_weights()

visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.compute_weights ( self,
torch.Tensor obj_descriptors )

Definition at line 130 of file XFeatVisualOdometry.py.

◆ display()

visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.display ( self,
CameraParameters cam,
ImageGray _I,
ImageRGBa IRGB,
ImageGray _I_depth )
Display the features used for visual odometry.
XFeat keypoints are displayed as small disks in the RGB image.

Depending on the display type, the behavior is different:
- DisplayType.SIMPLE: Display the current image keypoints that were matched with the environment map
- DisplayType.SIMPLE_MODEL_AND_PROJ: Display current image keypoints along with the map points that they were matched with.
- DisplayType.WEIGHT_AND_ERROR: Same as the SIMPLE value, except that the color of the keypoints display the error
(on the red component) and their attributed weight in the optimization (in blue)

Args:
    cam (CameraParameters): Camera intrinsics
    _I (ImageGray): Grayscale image
    IRGB (ImageRGBa): RGB image where to display the points
    _I_depth (ImageGray): Depth image

Raises:
    RuntimeError: if the display type is invalid

Definition at line 238 of file XFeatVisualOdometry.py.

References cTw, visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.current_representation, current_representation, visp.python.rbt.xfeat.RBXFeatFeatureTracker.RBXFeatFeatureTracker.display_type, display_type, environment_map, idx_curr_env_matched, and idx_environment_map.

◆ getCameraMotion()

HomogeneousMatrix visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.getCameraMotion ( self)

Definition at line 232 of file XFeatVisualOdometry.py.

References cnTc.

◆ getCameraPose()

HomogeneousMatrix visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.getCameraPose ( self)

Definition at line 235 of file XFeatVisualOdometry.py.

References cTw.

◆ load_settings()

◆ optimize()

visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.optimize ( self,
RBFeatureTrackerInput frame )

Definition at line 195 of file XFeatVisualOdometry.py.

◆ reset()

Member Data Documentation

◆ backend

visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.backend = backend

Definition at line 104 of file XFeatVisualOdometry.py.

Referenced by compute().

◆ cnTc

visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.cnTc = None

Definition at line 119 of file XFeatVisualOdometry.py.

Referenced by getCameraMotion(), and reset().

◆ cTw

visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.cTw = HomogeneousMatrix()

Definition at line 118 of file XFeatVisualOdometry.py.

Referenced by compute(), display(), getCameraPose(), and reset().

◆ current_representation

visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.current_representation = None

Definition at line 112 of file XFeatVisualOdometry.py.

Referenced by compute(), display(), and reset().

◆ display_type

visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.display_type = XFeatVisualOdometry.DisplayType.SIMPLE

Definition at line 110 of file XFeatVisualOdometry.py.

Referenced by display(), and load_settings().

◆ environment_map

visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.environment_map
Initial value:
= TrackedDescriptorMap(num_points=1024,
reprojection_threshold=10.0,
min_dist_new_point=0,
max_depth_error_visible=2e-2)

Definition at line 105 of file XFeatVisualOdometry.py.

Referenced by compute(), display(), load_settings(), and reset().

◆ idx_curr_env_matched

visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.idx_curr_env_matched

Definition at line 114 of file XFeatVisualOdometry.py.

Referenced by compute(), display(), and reset().

◆ idx_environment_map

visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.idx_environment_map = None, None

Definition at line 114 of file XFeatVisualOdometry.py.

Referenced by compute(), display(), and reset().

◆ iter

visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.iter = 0

Definition at line 115 of file XFeatVisualOdometry.py.

Referenced by compute(), and reset().

◆ numFeatures

int visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.numFeatures = 0

Definition at line 174 of file XFeatVisualOdometry.py.

◆ optim_params

visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.optim_params = LevenbergMarquardtParameters()

Definition at line 122 of file XFeatVisualOdometry.py.

Referenced by load_settings().

◆ previous_cTw

visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.previous_cTw = HomogeneousMatrix(self.cTw)

Definition at line 196 of file XFeatVisualOdometry.py.

Referenced by reset().

◆ use_3d

bool visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.use_3d = False

Definition at line 111 of file XFeatVisualOdometry.py.

Referenced by load_settings().

◆ Zs

list visp.python.rbt.xfeat.XFeatVisualOdometry.XFeatVisualOdometry.Zs = []

Definition at line 181 of file XFeatVisualOdometry.py.