diff --git a/src/yaml/processor_odom_3D_yaml.cpp b/src/yaml/processor_odom_3D_yaml.cpp
index ff564779517aa946365510c4a046c1cbc91de053..6ea8024a462b5db3fc583f7dee1e10504b2a4bfa 100644
--- a/src/yaml/processor_odom_3D_yaml.cpp
+++ b/src/yaml/processor_odom_3D_yaml.cpp
@@ -24,17 +24,20 @@ static ProcessorParamsBasePtr createProcessorOdom3DParams(const std::string & _f
 {
     YAML::Node config = YAML::LoadFile(_filename_dot_yaml);
 
-    if (config["processor type"].as<std::string>() == "ODOM 3D")
+    WOLF_TRACE("");
+    if (config["type"].as<std::string>() == "ODOM 3D")
     {
-        YAML::Node kf_vote = config["keyframe vote"];
+        WOLF_TRACE("");
+        YAML::Node kf_vote = config["keyframe_vote"];
+        WOLF_TRACE("");
 
         ProcessorParamsOdom3DPtr params = std::make_shared<ProcessorParamsOdom3D>();
 
-        params->time_tolerance      = config["time tolerance"]      .as<Scalar>();
-        params->max_time_span       = kf_vote["max time span"]      .as<Scalar>();
-        params->max_buff_length     = kf_vote["max buffer length"]  .as<SizeEigen  >();
-        params->dist_traveled       = kf_vote["dist traveled"]      .as<Scalar>();
-        params->angle_turned        = kf_vote["angle turned"]       .as<Scalar>();
+        params->time_tolerance      = config["time_tolerance"]      .as<Scalar>();
+        params->max_time_span       = kf_vote["max_time_span"]      .as<Scalar>();
+        params->max_buff_length     = kf_vote["max_buff_length"]    .as<SizeEigen  >();
+        params->dist_traveled       = kf_vote["dist_traveled"]      .as<Scalar>();
+        params->angle_turned        = kf_vote["angle_turned"]       .as<Scalar>();
 
         return params;
     }
diff --git a/src/yaml/sensor_odom_3D_yaml.cpp b/src/yaml/sensor_odom_3D_yaml.cpp
index 3756953b46cf952c900dca37569f8d51118509e4..623b03b3acf05fc9484b95182ee74b6a552e6eec 100644
--- a/src/yaml/sensor_odom_3D_yaml.cpp
+++ b/src/yaml/sensor_odom_3D_yaml.cpp
@@ -24,15 +24,15 @@ static IntrinsicsBasePtr createIntrinsicsOdom3D(const std::string & _filename_do
 {
     YAML::Node config = YAML::LoadFile(_filename_dot_yaml);
 
-    if (config["sensor type"].as<std::string>() == "ODOM 3D")
+    if (config["type"].as<std::string>() == "ODOM 3D")
     {
-        YAML::Node variances = config["motion variances"];
+        YAML::Node variances = config["motion_variances"];
 
         IntrinsicsOdom3DPtr params = std::make_shared<IntrinsicsOdom3D>();
 
-        params->k_disp_to_disp   = variances["disp_to_disp"] .as<Scalar>();
-        params->k_disp_to_rot    = variances["disp_to_rot"]  .as<Scalar>();
-        params->k_rot_to_rot     = variances["rot_to_rot"]   .as<Scalar>();
+        params->k_disp_to_disp   = variances["k_disp_to_disp"] .as<Scalar>();
+        params->k_disp_to_rot    = variances["k_disp_to_rot"]  .as<Scalar>();
+        params->k_rot_to_rot     = variances["k_rot_to_rot"]   .as<Scalar>();
         params->min_disp_var     = variances["min_disp_var"] .as<Scalar>();
         params->min_rot_var      = variances["min_rot_var"]  .as<Scalar>();
 
diff --git a/test/yaml/processor_odom_3D.yaml b/test/yaml/processor_odom_3D.yaml
index 7df9dd0218f3910c48a8559f5ee6af504989ed7b..f99f8edbefa98006c3d40d9f298dfb724dc8e04f 100644
--- a/test/yaml/processor_odom_3D.yaml
+++ b/test/yaml/processor_odom_3D.yaml
@@ -3,6 +3,6 @@ name: "Main odometer"        # This is ignored. The name provided to the SensorF
 time_tolerance:         0.01  # seconds
 keyframe_vote:
     max_time_span:      0.2   # seconds
-    max_buffer_length:  10    # motion deltas
+    max_buff_length:    10    # motion deltas
     dist_traveled:      0.5   # meters
     angle_turned:       0.1   # radians (1 rad approx 57 deg, approx 60 deg)
\ No newline at end of file
diff --git a/test/yaml/sensor_odom_3D.yaml b/test/yaml/sensor_odom_3D.yaml
index 075681ffb8b8162936d5d16301776e15f27a6a84..6a5424773897a00b5872ce0c07a2549bda40b5ee 100644
--- a/test/yaml/sensor_odom_3D.yaml
+++ b/test/yaml/sensor_odom_3D.yaml
@@ -1,8 +1,8 @@
 type: "ODOM 3D"              # This must match the KEY used in the SensorFactory. Otherwise it is an error.
 name: "Main odometer"        # This is ignored. The name provided to the SensorFactory prevails
 motion_variances: 
-    disp_to_disp:   0.02  # m^2   / m
-    disp_to_rot:    0.02  # rad^2 / m
-    rot_to_rot:     0.01  # rad^2 / rad
+    k_disp_to_disp:   0.02  # m^2   / m
+    k_disp_to_rot:    0.02  # rad^2 / m
+    k_rot_to_rot:     0.01  # rad^2 / rad
     min_disp_var:   0.01  # m^2
     min_rot_var:    0.01  # rad^2