mapPoints
Description
Examples
RGB-D Visual SLAM Using TUM RGB-D Data Set
Perform RGB-D visual simultaneous localization and mapping (vSLAM) using the data from the TUM RGB-D Benchmark. You can download the data to a temporary directory using a web browser or by running this code:
baseDownloadURL = "https://vision.in.tum.de/rgbd/dataset/freiburg3/rgbd_dataset_freiburg3_long_office_household.tgz"; dataFolder = fullfile(tempdir,"tum_rgbd_dataset",filesep); options = weboptions(Timeout=Inf); tgzFileName = dataFolder+"fr3_office.tgz"; folderExists = exist(dataFolder,"dir"); % Create a folder in a temporary directory to save the downloaded file if ~folderExists mkdir(dataFolder) disp("Downloading fr3_office.tgz (1.38 GB). This download can take a few minutes.") websave(tgzFileName,baseDownloadURL,options); % Extract contents of the downloaded file disp("Extracting fr3_office.tgz (1.38 GB) ...") untar(tgzFileName,dataFolder); end
Create two imageDatastore
objects. One to store the color images and the other to store the depth images.
colorImageFolder = dataFolder+"rgbd_dataset_freiburg3_long_office_household/rgb/"; depthImageFolder = dataFolder+"rgbd_dataset_freiburg3_long_office_household/depth/"; imdsColor = imageDatastore(colorImageFolder); imdsDepth = imageDatastore(depthImageFolder);
Select the synchronized pair of color and depth images.
data = load("rgbDepthPairs.mat");
imdsColor=subset(imdsColor, data.indexPairs(:, 1));
imdsDepth=subset(imdsDepth, data.indexPairs(:, 2));
Specify your camera intrinsic parameters, and use them to create an RGB-D visual SLAM object.
intrinsics = cameraIntrinsics([535.4 539.2],[320.1 247.6],[480 640]); depthScaleFactor = 5000; vslam = rgbdvslam(intrinsics,depthScaleFactor);
Process each pair of color and depth images, and visualize the camera poses and 3-D map points.
for i = 1:numel(imdsColor.Files) colorImage = readimage(imdsColor,i); depthImage = readimage(imdsDepth,i); addFrame(vslam,colorImage,depthImage); if hasNewKeyFrame(vslam) % Query 3-D map points and camera poses xyzPoints = mapPoints(vslam); [camPoses,viewIds] = poses(vslam); % Display 3-D map points and camera trajectory plot(vslam); end % Get current status of system status = checkStatus(vslam); % Stop adding frames when tracking is lost if status == uint8(0) break end end
Once all the frames have been processed, reset the system.
while ~isDone(vslam) plot(vslam); end reset(vslam);
Input Arguments
vslam
— RGB-D visual SLAM object
rgbdvslam
object
RGB-D visual SLAM object, specified as an rgbdvslam
object.
Output Arguments
xyzPoints
— World point coordinates of 3-D map
M-by-3 matrix
World point coordinates of 3-D map, returned as an M-by-3 matrix. M is the number of points, and each point is of the form [X Y Z].
Version History
Introduced in R2024a
See Also
Objects
Functions
addFrame
|hasNewKeyFrame
|checkStatus
|isDone
|poses
|plot
|reset
Topics
MATLAB Command
You clicked a link that corresponds to this MATLAB command:
Run the command by entering it in the MATLAB Command Window. Web browsers do not support MATLAB commands.
Select a Web Site
Choose a web site to get translated content where available and see local events and offers. Based on your location, we recommend that you select: .
You can also select a web site from the following list
How to Get Best Site Performance
Select the China site (in Chinese or English) for best site performance. Other MathWorks country sites are not optimized for visits from your location.
Americas
- América Latina (Español)
- Canada (English)
- United States (English)
Europe
- Belgium (English)
- Denmark (English)
- Deutschland (Deutsch)
- España (Español)
- Finland (English)
- France (Français)
- Ireland (English)
- Italia (Italiano)
- Luxembourg (English)
- Netherlands (English)
- Norway (English)
- Österreich (Deutsch)
- Portugal (English)
- Sweden (English)
- Switzerland
- United Kingdom (English)
Asia Pacific
- Australia (English)
- India (English)
- New Zealand (English)
- 中国
- 日本Japanese (日本語)
- 한국Korean (한국어)