diff --git a/src/lidar_lite_driver_node.cpp b/src/lidar_lite_driver_node.cpp
index 426f2225d9ef7dfa14bbaa7788d1ab3f39009bfb..fdc0a6959ef0b18dcb5e1ae862361c543819953a 100644
--- a/src/lidar_lite_driver_node.cpp
+++ b/src/lidar_lite_driver_node.cpp
@@ -12,10 +12,11 @@ LidarLiteDriverNode::LidarLiteDriverNode(ros::NodeHandle& nh)
   // Read from launch file
   std::string serial;
   int config_mode;
-  this->public_node_handle_.param<std::string>("lidar_lite_driver_node/serial_num", serial,
-                                               "A60124OL");
-  this->public_node_handle_.param<int>("lidar_lite_driver_node/config_mode", config_mode, 0);
-  this->public_node_handle_.param<std::string>("lidar_lite_driver_node/frame_id", this->frame_id_,
+  ros::NodeHandle node_handle;
+  node_handle.param<std::string>("/iri_lidar_lite_driver/serial_num", serial,
+                                               "");
+  node_handle.param<int>("/iri_lidar_lite_driver/config_mode", config_mode, 0);
+  node_handle.param<std::string>("/iri_lidar_lite_driver/frame_id", this->frame_id_,
                                                "lidar_lite");
 
   // Set device parameters
@@ -23,7 +24,7 @@ LidarLiteDriverNode::LidarLiteDriverNode(ros::NodeHandle& nh)
 
   // [init publishers]
   this->range_publisher_ =
-    this->public_node_handle_.advertise<sensor_msgs::Range>("range", 100);
+    this->public_node_handle_.advertise<sensor_msgs::Range>("lidarlite_range/range", 100);
   this->range_seq_ = 0;
 
   // [init subscribers]