Difference between revisions of "Example Stereo Visual Odometry"
From BoofCV
Jump to navigationJump to searchm |
m |
||
(18 intermediate revisions by the same user not shown) | |||
Line 1: | Line 1: | ||
<center> | <center> | ||
<gallery widths=758px heights=384px > | <gallery widths=758px heights=384px > | ||
File:Stereo_visual_odometry_screenshot.jpg|Screenshot from visual odometry | File:Stereo_visual_odometry_screenshot.jpg|Screenshot from visual odometry demonstration. Red squares are camera locations and colorized dots are part of sparse reconstruction used to estimate motion. | ||
</gallery> | </gallery> | ||
</center> | </center> | ||
Stereo visual odometry estimates the camera's egomotion using a pair of calibrated cameras. Stereo camera systems are | Stereo visual odometry estimates the camera's egomotion using a pair of calibrated cameras. Stereo camera systems are inherently more stable than monocular ones because the stereo pair provides good triangulation of image features and resolves the scale ambiguity. The example below shows how to use a high level interface with visual odometry algorithms. The basic high level interface hides internal data structures which are useful in many applications, which is why an optional interface is provided for accessing some of those structures. | ||
Example File: [https://github.com/lessthanoptimal/BoofCV/blob/ | Example File: [https://github.com/lessthanoptimal/BoofCV/blob/v0.37/examples/src/main/java/boofcv/examples/sfm/ExampleVisualOdometryStereo.java ExampleVisualOdometryStereo.java] | ||
Concepts: | Concepts: | ||
Line 16: | Line 14: | ||
* Feature Tracking | * Feature Tracking | ||
Relevant | Relevant Videos: | ||
* [ | * [https://www.youtube.com/watch?v=8pn9Ebw90uk&t=292s Video 2020] | ||
* [https://www.youtube.com/watch?v=D4I4NHSGaOc Video 2013] | |||
Related Tutorials/Example Code: | Related Tutorials/Example Code: | ||
* [[Tutorial_Geometric_Vision| Tutorial Geometric Vision]] | * [[Tutorial_Geometric_Vision| Tutorial Geometric Vision]] | ||
* [[Example Visual Odometry Monocular Plane| Visual Odometry Monocular Plane]] | |||
* [[Example Visual Odometry Depth| Visual Odometry Depth]] | |||
= Example Code = | |||
<syntaxhighlight lang="java"> | <syntaxhighlight lang="java"> | ||
Line 31: | Line 32: | ||
* @author Peter Abeles | * @author Peter Abeles | ||
*/ | */ | ||
public class | public class ExampleVisualOdometryStereo { | ||
public static void main( String[] args ) { | |||
MediaManager media = DefaultMediaManager.INSTANCE; | |||
String directory = UtilIO.pathExample("vo/backyard/"); | |||
// load camera description and the video sequence | |||
StereoParameters stereoParam = CalibrationIO.load(media.openFile(new File(directory, "stereo.yaml").getPath())); | |||
SimpleImageSequence<GrayU8> video1 = media.openVideo( | |||
new File(directory, "left.mjpeg").getPath(), ImageType.single(GrayU8.class)); | |||
SimpleImageSequence<GrayU8> video2 = media.openVideo( | |||
new File(directory, "right.mjpeg").getPath(), ImageType.single(GrayU8.class)); | |||
// Specify which tracker and how it will behave | |||
var configKlt = new ConfigPKlt(); | |||
configKlt.pyramidLevels = ConfigDiscreteLevels.levels(4); | |||
configKlt.templateRadius = 4; | |||
configKlt.toleranceFB = 3; | |||
configKlt.pruneClose = true; | |||
var configDet = new ConfigPointDetector(); | |||
configDet.type = PointDetectorTypes.SHI_TOMASI; | |||
configDet.shiTomasi.radius = 4; | |||
configDet.general.maxFeatures = 300; | |||
configDet.general.radius = 5; | |||
// | // We will estimate the location of features using block matching stereo | ||
var configBM = new ConfigDisparityBM(); | |||
configBM.errorType = DisparityError.CENSUS; | |||
configBM.disparityMin = 0; | |||
configBM.disparityRange = 50; | |||
configBM.regionRadiusX = 3; | |||
configBM.regionRadiusY = 3; | |||
configBM.maxPerPixelError = 30; | |||
configBM.texture = 0.05; | |||
configBM.validateRtoL = 1; | |||
configBM.subpixel = true; | |||
// | // Configurations related to how the structure is chained together frame to frame | ||
var configVisOdom = new ConfigVisOdomTrackPnP(); | |||
configVisOdom.keyframes.geoMinCoverage = 0.4; | |||
configVisOdom.ransac.iterations = 200; | |||
configVisOdom.ransac.inlierThreshold = 1.0; | |||
// | // Declare each component then visual odometry | ||
StereoDisparitySparse< | PointTracker<GrayU8> tracker = FactoryPointTracker.klt(configKlt, configDet, GrayU8.class, GrayS16.class); | ||
StereoDisparitySparse<GrayU8> disparity = FactoryStereoDisparity.sparseRectifiedBM(configBM, GrayU8.class); | |||
StereoVisualOdometry<GrayU8> visodom = FactoryVisualOdometry.stereoMonoPnP(configVisOdom, disparity, tracker, GrayU8.class); | |||
// | // Optionally dump verbose debugging information to stdout | ||
// Set<String> configuration = new HashSet<>(); | |||
// configuration.add(VisualOdometry.VERBOSE_RUNTIME); | |||
// configuration.add(VisualOdometry.VERBOSE_TRACKING); | |||
// visodom.setVerbose(System.out,configuration); | |||
// Pass in intrinsic/extrinsic calibration. This can be changed in the future. | // Pass in intrinsic/extrinsic calibration. This can be changed in the future. | ||
visodom.setCalibration(stereoParam); | |||
// Process the video sequence and output the location plus number of inliers | // Process the video sequence and output the location plus number of inliers | ||
while( video1.hasNext() ) { | long startTime = System.nanoTime(); | ||
while (video1.hasNext()) { | |||
GrayU8 left = video1.next(); | |||
GrayU8 right = video2.next(); | |||
if( ! | if (!visodom.process(left, right)) { | ||
throw new RuntimeException("VO Failed!"); | throw new RuntimeException("VO Failed!"); | ||
} | } | ||
Se3_F64 leftToWorld = | Se3_F64 leftToWorld = visodom.getCameraToWorld(); | ||
Vector3D_F64 T = leftToWorld.getT(); | Vector3D_F64 T = leftToWorld.getT(); | ||
System.out.printf("Location %8.2f %8.2f %8.2f | System.out.printf("Location %8.2f %8.2f %8.2f %s\n", T.x, T.y, T.z, trackStats(visodom)); | ||
} | } | ||
System.out.printf("FPS %4.2f\n", video1.getFrameNumber()/((System.nanoTime() - startTime)*1e-9)); | |||
} | } | ||
/** | /** | ||
* If the algorithm implements AccessPointTracks3D | * If the algorithm implements AccessPointTracks3D create a string which summarizing different tracking information | ||
*/ | */ | ||
public static String | public static String trackStats( StereoVisualOdometry alg ) { | ||
if( !(alg instanceof AccessPointTracks3D)) | if (!(alg instanceof AccessPointTracks3D)) | ||
return ""; | return ""; | ||
Line 86: | Line 118: | ||
int count = 0; | int count = 0; | ||
int N = access. | int N = access.getTotalTracks(); | ||
for( int i = 0; i < N; i++ ) { | int totalNew = 0; | ||
if( access. | for (int i = 0; i < N; i++) { | ||
if (access.isTrackInlier(i)) | |||
count++; | count++; | ||
else if (access.isTrackNew(i)) { | |||
totalNew++; | |||
} | |||
} | } | ||
return | return String.format("inlier %5.1f%% new %4d total %d", 100.0*count/(N - totalNew), totalNew, N); | ||
} | } | ||
} | } | ||
</syntaxhighlight> | </syntaxhighlight> |
Revision as of 19:45, 21 December 2020
Stereo visual odometry estimates the camera's egomotion using a pair of calibrated cameras. Stereo camera systems are inherently more stable than monocular ones because the stereo pair provides good triangulation of image features and resolves the scale ambiguity. The example below shows how to use a high level interface with visual odometry algorithms. The basic high level interface hides internal data structures which are useful in many applications, which is why an optional interface is provided for accessing some of those structures.
Example File: ExampleVisualOdometryStereo.java
Concepts:
- Structure from Motion
- Geometric Vision
- Feature Tracking
Relevant Videos:
Related Tutorials/Example Code:
Example Code
/**
* Bare bones example showing how to estimate the camera's ego-motion using a stereo camera system. Additional
* information on the scene can be optionally extracted from the algorithm if it implements AccessPointTracks3D.
*
* @author Peter Abeles
*/
public class ExampleVisualOdometryStereo {
public static void main( String[] args ) {
MediaManager media = DefaultMediaManager.INSTANCE;
String directory = UtilIO.pathExample("vo/backyard/");
// load camera description and the video sequence
StereoParameters stereoParam = CalibrationIO.load(media.openFile(new File(directory, "stereo.yaml").getPath()));
SimpleImageSequence<GrayU8> video1 = media.openVideo(
new File(directory, "left.mjpeg").getPath(), ImageType.single(GrayU8.class));
SimpleImageSequence<GrayU8> video2 = media.openVideo(
new File(directory, "right.mjpeg").getPath(), ImageType.single(GrayU8.class));
// Specify which tracker and how it will behave
var configKlt = new ConfigPKlt();
configKlt.pyramidLevels = ConfigDiscreteLevels.levels(4);
configKlt.templateRadius = 4;
configKlt.toleranceFB = 3;
configKlt.pruneClose = true;
var configDet = new ConfigPointDetector();
configDet.type = PointDetectorTypes.SHI_TOMASI;
configDet.shiTomasi.radius = 4;
configDet.general.maxFeatures = 300;
configDet.general.radius = 5;
// We will estimate the location of features using block matching stereo
var configBM = new ConfigDisparityBM();
configBM.errorType = DisparityError.CENSUS;
configBM.disparityMin = 0;
configBM.disparityRange = 50;
configBM.regionRadiusX = 3;
configBM.regionRadiusY = 3;
configBM.maxPerPixelError = 30;
configBM.texture = 0.05;
configBM.validateRtoL = 1;
configBM.subpixel = true;
// Configurations related to how the structure is chained together frame to frame
var configVisOdom = new ConfigVisOdomTrackPnP();
configVisOdom.keyframes.geoMinCoverage = 0.4;
configVisOdom.ransac.iterations = 200;
configVisOdom.ransac.inlierThreshold = 1.0;
// Declare each component then visual odometry
PointTracker<GrayU8> tracker = FactoryPointTracker.klt(configKlt, configDet, GrayU8.class, GrayS16.class);
StereoDisparitySparse<GrayU8> disparity = FactoryStereoDisparity.sparseRectifiedBM(configBM, GrayU8.class);
StereoVisualOdometry<GrayU8> visodom = FactoryVisualOdometry.stereoMonoPnP(configVisOdom, disparity, tracker, GrayU8.class);
// Optionally dump verbose debugging information to stdout
// Set<String> configuration = new HashSet<>();
// configuration.add(VisualOdometry.VERBOSE_RUNTIME);
// configuration.add(VisualOdometry.VERBOSE_TRACKING);
// visodom.setVerbose(System.out,configuration);
// Pass in intrinsic/extrinsic calibration. This can be changed in the future.
visodom.setCalibration(stereoParam);
// Process the video sequence and output the location plus number of inliers
long startTime = System.nanoTime();
while (video1.hasNext()) {
GrayU8 left = video1.next();
GrayU8 right = video2.next();
if (!visodom.process(left, right)) {
throw new RuntimeException("VO Failed!");
}
Se3_F64 leftToWorld = visodom.getCameraToWorld();
Vector3D_F64 T = leftToWorld.getT();
System.out.printf("Location %8.2f %8.2f %8.2f %s\n", T.x, T.y, T.z, trackStats(visodom));
}
System.out.printf("FPS %4.2f\n", video1.getFrameNumber()/((System.nanoTime() - startTime)*1e-9));
}
/**
* If the algorithm implements AccessPointTracks3D create a string which summarizing different tracking information
*/
public static String trackStats( StereoVisualOdometry alg ) {
if (!(alg instanceof AccessPointTracks3D))
return "";
AccessPointTracks3D access = (AccessPointTracks3D)alg;
int count = 0;
int N = access.getTotalTracks();
int totalNew = 0;
for (int i = 0; i < N; i++) {
if (access.isTrackInlier(i))
count++;
else if (access.isTrackNew(i)) {
totalNew++;
}
}
return String.format("inlier %5.1f%% new %4d total %d", 100.0*count/(N - totalNew), totalNew, N);
}
}