From e552003c6035465a4c05cd1e5d20ec9f5a795395 Mon Sep 17 00:00:00 2001
From: Jim Radford <jim.radford@intel.com>
Date: Mon, 9 Dec 2019 11:01:38 -0800
Subject: [PATCH 1/2] doc/t265.md: document RS2_OPTION_ENABLE_MAP_PRESERVATION

---
 doc/t265.md | 1 +
 1 file changed, 1 insertion(+)

diff --git a/doc/t265.md b/doc/t265.md
index 8d1526150a..683445a1e2 100644
--- a/doc/t265.md
+++ b/doc/t265.md
@@ -156,6 +156,7 @@ Yes, there are.
  - `RS2_OPTION_ENABLE_MAPPING`  - The internal map allows the device to recognize places it's been before so that it can give a consistent pose for that location.   The map has a fixed finite size and will keep the most often/recently seen locations.  Without this it will be operating completely open loop (i.e. just doing VIO) and will have more drift.   The device will use the map to close modest loops and recover from small drifts.  Enabling this option will not cause pose jumps without `RS2_OPTION_ENABLE_POSE_JUMPING`.
  - `RS2_OPTION_ENABLE_POSE_JUMPING` - This option allows the device to discontinuously jump its pose whenever it discovers its pose is inconsistent with one it has given before.   For example, after walking in a circle or covering the camera (getting a small drift) and uncovering it.  Currently this will only affect the translation and not the rotation nor any of the velocities or accelerations.
  - `RS2_OPTION_ENABLE_RELOCALIZATION` - This allows the device to solve the Kidnapped Robot Problem, i.e. it will allow connecting the current map to a loaded map or connecting the current map to itself after accumulating a large drift, say after closing a large loop or covering the camera and walking around.  This is independent of jumping the pose.  When fooled this feature can lead to much larger errors than are likely via the basic mapping.
+ - `RS2_OPTION_ENABLE_MAP_PRESERVATION` - This option will allow the device to preserve its current map across stop/start calls.  The device will act as if the map was saved after stop and loaded back before the subsequent start.  This was the default in versions <= 2.29.0.
 
 ## Appendix
 

From 3b3c64c24039b6ac27f6cd1ca08d3a5c8200ba76 Mon Sep 17 00:00:00 2001
From: Brian Fulkerson <brian.fulkerson@intel.com>
Date: Thu, 5 Dec 2019 14:10:09 +0000
Subject: [PATCH 2/2] tm-device: Option toggle order is {min, max, step,
 default}

---
 src/tm2/tm-device.cpp | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/src/tm2/tm-device.cpp b/src/tm2/tm-device.cpp
index 4b089d41b2..05f3061eb0 100644
--- a/src/tm2/tm-device.cpp
+++ b/src/tm2/tm-device.cpp
@@ -201,7 +201,7 @@ namespace librealsense
         bool is_read_only() const override { return s._is_streaming; }
 
         explicit tracking_mode_option(tm2_sensor& sensor, const char *description_) :
-            s(sensor), description(description_), option_base(option_range{ 0, 1, !!(sensor._tm_mode & flag) ^ invert ? 1.f : 0.f, 1 }) { }
+            s(sensor), description(description_), option_base(option_range{ 0, 1, 1, !!(sensor._tm_mode & flag) ^ invert ? 1.f : 0.f }) { }
 
     private:
         tm2_sensor &s;