Package boofcv.factory.sfm
Class ConfigStereoMonoTrackPnP
java.lang.Object
boofcv.factory.sfm.ConfigStereoMonoTrackPnP
- All Implemented Interfaces:
Configuration
,Serializable
Configuration for
WrapVisOdomMonoStereoDepthPnP
. Stereo visual odometry where features
are tracked only in the left camera. The right camera is only used for the initial depth estimate of a new
feature and ignored otherwise.- See Also:
-
Field Summary
Modifier and TypeFieldDescriptionConfiguration for stereo disparity calculationConfiguration for building and optimizing a local sceneTracker configuration for left camera -
Constructor Summary
-
Method Summary
Modifier and TypeMethodDescriptionvoid
Checks to see if the configuration is valid.Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
Methods inherited from interface boofcv.struct.Configuration
serializeActiveFields, serializeInitialize
-
Field Details
-
scene
Configuration for building and optimizing a local scene -
tracker
Tracker configuration for left camera -
disparity
Configuration for stereo disparity calculation
-
-
Constructor Details
-
ConfigStereoMonoTrackPnP
public ConfigStereoMonoTrackPnP()
-
-
Method Details
-
checkValidity
public void checkValidity()Description copied from interface:Configuration
Checks to see if the configuration is valid. If it is invalid, throw an exception explaining what is incorrect.- Specified by:
checkValidity
in interfaceConfiguration
-
setTo
-