diff --git a/include/laser/sensor/sensor_laser_2D.h b/include/laser/sensor/sensor_laser_2D.h
index fa4913736945bf2a620db3ae4f08d90570052be4..3fd5c68f30c0896c4e25ae9f3e11ffa0d553ff91 100644
--- a/include/laser/sensor/sensor_laser_2D.h
+++ b/include/laser/sensor/sensor_laser_2D.h
@@ -36,15 +36,15 @@ struct IntrinsicsLaser2D : public IntrinsicsBase
         }
         std::string print()
         {
-            return "\n" + IntrinsicsBase::print()                                   + "\n"
-            + "angle_min: "         + std::to_string(scan_params.angle_min_)        + "\n"
-            + "angle_max: "         + std::to_string(scan_params.angle_max_)        + "\n"
-            + "angle_step: "        + std::to_string(scan_params.angle_step_)       + "\n"
-            + "scan_time: "         + std::to_string(scan_params.scan_time_)        + "\n"
-            + "range_min: "         + std::to_string(scan_params.range_min_)        + "\n"
-            + "range_max: "         + std::to_string(scan_params.range_max_)        + "\n"
-            + "range_std_dev: "     + std::to_string(scan_params.range_std_dev_)    + "\n"
-            + "angle_std_dev: "     + std::to_string(scan_params.angle_std_dev_)    + "\n";
+            return "\n" + IntrinsicsBase::print()                                                   + "\n"
+            + "LaserScanParams/angle_min: "         + std::to_string(scan_params.angle_min_)        + "\n"
+            + "LaserScanParams/angle_max: "         + std::to_string(scan_params.angle_max_)        + "\n"
+            + "LaserScanParams/angle_step: "        + std::to_string(scan_params.angle_step_)       + "\n"
+            + "LaserScanParams/scan_time: "         + std::to_string(scan_params.scan_time_)        + "\n"
+            + "LaserScanParams/range_min: "         + std::to_string(scan_params.range_min_)        + "\n"
+            + "LaserScanParams/range_max: "         + std::to_string(scan_params.range_max_)        + "\n"
+            + "LaserScanParams/range_std_dev: "     + std::to_string(scan_params.range_std_dev_)    + "\n"
+            + "LaserScanParams/angle_std_dev: "     + std::to_string(scan_params.angle_std_dev_)    + "\n";
         }
 
 };