diff --git a/src/examples/camera_logitech_c300_640_480.yaml b/src/examples/camera_logitech_c300_640_480.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..5f8a1899b71df3721e6f9722d39bd8e09e34509a
--- /dev/null
+++ b/src/examples/camera_logitech_c300_640_480.yaml
@@ -0,0 +1,22 @@
+image_width: 640
+image_height: 480
+#camera_name: narrow_stereo
+camera_name: camera
+camera_matrix:
+  rows: 3
+  cols: 3
+  data: [711.687376, 0.000000, 323.306816, 0.000000, 710.933260, 232.005822, 0.000000, 0.000000, 1.000000]
+distortion_model: plumb_bob
+distortion_coefficients:
+  rows: 1
+  cols: 5
+  data: [0.067204, -0.141639, 0, 0, 0]
+#  data: [0.067204, -0.141639, 0.004462, -0.000636, 0.000000]
+rectification_matrix:
+  rows: 3
+  cols: 3
+  data: [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000]
+projection_matrix:
+  rows: 3
+  cols: 4
+  data: [718.941772, 0.000000, 323.016804, 0.000000, 0.000000, 717.174622, 233.475721, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
diff --git a/src/examples/maps/map_apriltag_logitech_1234.yaml b/src/examples/maps/map_apriltag_logitech_1234.yaml
index 850c04adf9e76e6588cae936acb5086d4caf51e0..f313d1a11a3f2b4fa239f710cbbea7372747677d 100644
--- a/src/examples/maps/map_apriltag_logitech_1234.yaml
+++ b/src/examples/maps/map_apriltag_logitech_1234.yaml
@@ -3,8 +3,8 @@ map name: "4 tags printed on a A4 sheet vertical recorded at IRI with logitech w
 nlandmarks: 4          # This must match the number of landmarks in the list that follows. Otherwise it is an error.
 
 ######################
-# World frame is considered to be at 75cm from the sheet with RDF convention (like a camera). 
-# Landmarks facing the Z axis (view axis of the camera) have the same orientation as world frame.
+# World frame is considered to be the top left corner of tag id 0. Reference frame is corherent with a camera
+# looking straight at the sheet with RBF convention.
 ######################
 landmarks:
 
@@ -12,7 +12,7 @@ landmarks:
     type: "APRILTAG"          # This must match the KEY used in the LandmarkFactory. Otherwise it is an error.
     tag id: 0
     tag width: 0.055
-    position: [-0.061, -0.185, 0.75]
+    position: [0.0225, 0.0225, 0]
     orientation: [0, 0, 0]    # roll pitch yaw in degrees
     position fixed: true
     orientation fixed: true
@@ -21,7 +21,7 @@ landmarks:
     type: "APRILTAG"          # This must match the KEY used in the LandmarkFactory. Otherwise it is an error.
     tag id: 1
     tag width: 0.055
-    position: [0.061, -0.185, 0.75]
+    position: [0.1525, 0.0225, 0]
     orientation: [0, 0, 0]    # roll pitch yaw in degrees
     position fixed: true
     orientation fixed: true
@@ -30,7 +30,7 @@ landmarks:
     type: "APRILTAG"          # This must match the KEY used in the LandmarkFactory. Otherwise it is an error.
     tag id: 2
     tag width: 0.055
-    position: [-0.061, 0, 0.75]
+    position: [0.0225, 0.2125, 0]
     orientation: [0, 0, 0]    # roll pitch yaw in degrees
     position fixed: true
     orientation fixed: true
@@ -39,7 +39,7 @@ landmarks:
     type: "APRILTAG"          # This must match the KEY used in the LandmarkFactory. Otherwise it is an error.
     tag id: 3
     tag width: 0.055
-    position: [0.061, 0, 0.75]
+    position: [0.1525, 0.2125, 0]
     orientation: [0, 0, 0]    # roll pitch yaw in degrees
     position fixed: true
     orientation fixed: true
diff --git a/src/examples/test_apriltag.cpp b/src/examples/test_apriltag.cpp
index 2a71fa5832face827c8d14ccbc1b5b6e10914c84..4964ce4cd77943a5a863d3a09992ef6c9edcabfc 100644
--- a/src/examples/test_apriltag.cpp
+++ b/src/examples/test_apriltag.cpp
@@ -74,7 +74,8 @@ int main(int argc, char *argv[])
     covariance.topLeftCorner(3,3)       =  stdev_m*stdev_m * covariance.topLeftCorner(3,3);
     covariance.bottomRightCorner(3,3)   = (M_TORAD*stdev_deg)*(M_TORAD*stdev_deg) * covariance.bottomRightCorner(3,3);
 
-    FrameBasePtr F1 = problem->setPrior((Vector7s()<<0,0,0,0,0,0,1).finished(), covariance, 0.0, 0.1);
+//    FrameBasePtr F1 = problem->setPrior((Vector7s()<<0,0,0,0,0,0,1).finished(), covariance, 0.0, 0.1);
+    FrameBasePtr F1 = problem->setPrior((Vector7s()<<0.08, 0, -0.75, 0, 0, 0, 1).finished(), covariance, 0.0, 0.1);
 
     // first argument is the name of the program.
     // following arguments are path to image (from wolf_root)