diff --git a/CMakeLists.txt b/CMakeLists.txt
index 016e74354d..3f9300410c 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -193,6 +193,11 @@ add_executable(mono_tum
Examples/Monocular/mono_tum.cc)
target_link_libraries(mono_tum ${PROJECT_NAME})
+add_executable(mono_webcam
+ Examples/Monocular/mono_webcam.cc)
+
+target_link_libraries(mono_webcam ${PROJECT_NAME})
+
add_executable(mono_kitti
Examples/Monocular/mono_kitti.cc)
target_link_libraries(mono_kitti ${PROJECT_NAME})
diff --git a/Examples/Monocular/mono_webcam.cc b/Examples/Monocular/mono_webcam.cc
new file mode 100644
index 0000000000..b23aa6f48e
--- /dev/null
+++ b/Examples/Monocular/mono_webcam.cc
@@ -0,0 +1,101 @@
+/**
+ * This file is part of ORB-SLAM3
+ *
+ * Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
+ * Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
+ *
+ * ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
+ * License as published by the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
+ * the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License along with ORB-SLAM3.
+ * If not, see .
+ */
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include
+#include
+#include
+
+using namespace std;
+
+bool b_continue_session = true;
+
+void exit_loop_handler(int s)
+{
+ cout << "Finishing session" << endl;
+ b_continue_session = false;
+}
+
+int main(int argc, char **argv)
+{
+
+ if (argc < 3 || argc > 4)
+ {
+ cerr << endl
+ << "Usage: ./mono_webcam path_to_vocabulary path_to_settings (trajectory_file_name)" << endl;
+ return 1;
+ }
+
+ string file_name;
+ bool bFileName = false;
+
+ if (argc == 4)
+ {
+ file_name = string(argv[argc - 1]);
+ bFileName = true;
+ }
+
+ // Set video capture to interface 0 (default)
+ cv::VideoCapture cap(0);
+
+ if (!cap.isOpened()) {
+ std::cout << "Cannot open camera";
+ return 1;
+ }
+
+
+ cout.precision(17);
+
+ // Create SLAM system. It initializes all system threads and gets ready to process frames.
+ // ORB_SLAM3::System SLAM("../../Vocabulary/ORBvoc.txt", "webcam.yaml", ORB_SLAM3::System::MONOCULAR, true);
+ ORB_SLAM3::System SLAM(argv[1], argv[2], ORB_SLAM3::System::MONOCULAR, true);
+ float imageScale = SLAM.GetImageScale();
+
+ cv::Mat imCV;
+
+ double t_resize = 0.f;
+ double t_track = 0.f;
+
+ while (b_continue_session)
+ {
+ double timestamp_ms = chrono::duration_cast(chrono::system_clock::now().time_since_epoch()).count();
+ cap >> imCV;
+ if (imageScale != 1.f)
+ {
+ int width = imCV.cols * imageScale;
+ int height = imCV.rows * imageScale;
+ cv::resize(imCV, imCV, cv::Size(width, height));
+ }
+
+ // Pass the image to the SLAM system
+ SLAM.TrackMonocular(imCV, timestamp_ms);
+ }
+
+ // Stop all threads
+ SLAM.Shutdown();
+
+ return 0;
+}
diff --git a/Examples/Monocular/webcam.yaml b/Examples/Monocular/webcam.yaml
new file mode 100755
index 0000000000..5a1ef8d81c
--- /dev/null
+++ b/Examples/Monocular/webcam.yaml
@@ -0,0 +1,67 @@
+%YAML:1.0
+
+#--------------------------------------------------------------------------------------------
+# Camera Parameters. Adjust them!
+#--------------------------------------------------------------------------------------------
+File.version: "1.0"
+
+Camera.type: "PinHole"
+
+# Left Camera calibration and distortion parameters (OpenCV)
+Camera1.fx: 472.0697
+Camera1.fy: 469.5124
+Camera1.cx: 325.8198
+Camera1.cy: 231.6289
+
+# distortion parameters
+Camera1.k1: 0.09889
+Camera1.k2: -0.19307
+Camera1.p1: -0.011889
+Camera1.p2: 0.003196
+Camera1.k3: -0.066268
+
+# Camera resolution
+Camera.width: 640
+Camera.height: 480
+
+# Camera frames per second
+Camera.fps: 30
+
+# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
+Camera.RGB: 1
+
+#--------------------------------------------------------------------------------------------
+# ORB Parameters
+#--------------------------------------------------------------------------------------------
+# ORB Extractor: Number of features per image
+ORBextractor.nFeatures: 1250
+
+# ORB Extractor: Scale factor between levels in the scale pyramid
+ORBextractor.scaleFactor: 1.2
+
+# ORB Extractor: Number of levels in the scale pyramid
+ORBextractor.nLevels: 12
+
+# ORB Extractor: Fast threshold
+# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
+# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
+# You can lower these values if your images have low contrast
+ORBextractor.iniThFAST: 20
+ORBextractor.minThFAST: 7
+
+#--------------------------------------------------------------------------------------------
+# Viewer Parameters
+#--------------------------------------------------------------------------------------------
+Viewer.KeyFrameSize: 0.05
+Viewer.KeyFrameLineWidth: 1.0
+Viewer.GraphLineWidth: 0.9
+Viewer.PointSize: 2.0
+Viewer.CameraSize: 0.08
+Viewer.CameraLineWidth: 3.0
+Viewer.ViewpointX: 0.0
+Viewer.ViewpointY: -0.7
+Viewer.ViewpointZ: -3.5
+Viewer.ViewpointF: 500.0
+
+# System.LoadAtlasFromFile: "./atlas"
+# System.SaveAtlasToFile: "./atlas"
\ No newline at end of file
diff --git a/README.md b/README.md
index 0ca3a9f2d3..5b5b769eec 100644
--- a/README.md
+++ b/README.md
@@ -110,6 +110,10 @@ Directory `Examples` contains several demo programs and calibration files to run
```
./Examples/Stereo-Inertial/stereo_inertial_realsense_D435i Vocabulary/ORBvoc.txt ./Examples/Stereo-Inertial/RealSense_D435i.yaml
```
+Note: If you just want to try ORB-SLAM3 with your webcam, you can use the generic webcam example, which read the default webcam interface. You also need to modify the `webcam.yaml` file with your own calibration in order to get proper results.
+```
+./Examples/Monocular/mono_webcam Vocabulary/ORBvoc.txt ./Examples/Monocular/webcam.yaml
+```
# 5. EuRoC Examples
[EuRoC dataset](http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets) was recorded with two pinhole cameras and an inertial sensor. We provide an example script to launch EuRoC sequences in all the sensor configurations.