diff --git a/include/vision/capture/capture_image.h b/include/vision/capture/capture_image.h
index 97b569577314c509552428b69c31cd93bbf814ff..66415c5d7c0a16702c4c0630557ea461b0999cd3 100644
--- a/include/vision/capture/capture_image.h
+++ b/include/vision/capture/capture_image.h
@@ -68,8 +68,12 @@ class WKeyPoint
 };
 
 
-
+// This map is frame specific and enables to recover a Wolf KeyPoint with a certain
+// ID in a frame
 typedef std::unordered_map<size_t, WKeyPoint> KeyPointsMap;
+
+// This maps the IDs of the Wolf KeyPoints that are tracked from a frame to the other.
+// It takes the ID of a WKeyPoint and returns the ID of its track in another Frame.
 typedef std::unordered_map<size_t, size_t> TracksMap;
 
 // Set ClassPtr, ClassConstPtr and ClassWPtr typedefs;
diff --git a/src/processor/processor_visual_odometry.cpp b/src/processor/processor_visual_odometry.cpp
index f42814743a7a5dd994b9e3237fd7d0a167e06727..5db79afa9bde2d410897f2c79b626e0cfb64c532 100644
--- a/src/processor/processor_visual_odometry.cpp
+++ b/src/processor/processor_visual_odometry.cpp
@@ -125,11 +125,16 @@ void ProcessorVisualOdometry::preProcess()
     //   - ...
     ////////////////////////////////
 
-    // Tracks between last and incoming
+    // TracksMap between last and incoming
+    // Input: ID of Wkp in last. Output: ID of the tracked Wkp in incoming.
     TracksMap tracks_last_incoming = kltTrack(img_last, img_incoming, mwkps_last, mwkps_incoming);
 
-    // Merge tracks to get tracks_origin_incoming
+    // TracksMap between origin and last
+    // Input: ID of Wkp in origin. Output: ID of the tracked Wkp in last.
     TracksMap tracks_origin_last = capture_image_last_->getTracksOrigin();
+
+    // Merge tracks to get TracksMap between origin and incoming
+    // Input: ID of Wkp in origin. Output: ID of the tracked Wkp in incoming.
     TracksMap tracks_origin_incoming = mergeTracks(tracks_origin_last, tracks_last_incoming);
 
     // Outliers rejection with essential matrix