From 5a85592a9dbfd2d2b990bf59f3a41362a35ecc3c Mon Sep 17 00:00:00 2001
From: asantamaria <angel.santamaria.navarro@jpl.nasa.gov>
Date: Tue, 16 Apr 2019 10:13:56 -0700
Subject: [PATCH] Update code according with new driver naming convention

---
 include/lidar_lite_driver.h    |  4 ++--
 launch/iri_lidar_lite.launch   |  1 +
 src/lidar_lite_driver_node.cpp | 10 +++++-----
 3 files changed, 8 insertions(+), 7 deletions(-)

diff --git a/include/lidar_lite_driver.h b/include/lidar_lite_driver.h
index a1a0d88..176afab 100644
--- a/include/lidar_lite_driver.h
+++ b/include/lidar_lite_driver.h
@@ -30,8 +30,8 @@
 #include <iri_base_driver/iri_base_driver.h>
 #include <iri_lidar_lite_driver/LidarLiteDriverConfig.h>
 
-#include <iridrivers/lidar_lite.h>
-#include <iridrivers/lidar_lite_exceptions.h>
+#include <iridrivers/lidar_lite/lidar_lite.h>
+#include <iridrivers/lidar_lite/lidar_lite_exceptions.h>
 
 /**
  * \brief IRI ROS Specific Driver Class
diff --git a/launch/iri_lidar_lite.launch b/launch/iri_lidar_lite.launch
index 57f50ca..4b5197b 100644
--- a/launch/iri_lidar_lite.launch
+++ b/launch/iri_lidar_lite.launch
@@ -2,6 +2,7 @@
 
 <launch>
 
+  <node pkg="iri_lidar_lite_driver" type="iri_lidar_lite_driver" name="iri_lidar_lite_driver" output="screen">
   <node pkg="iri_lidar_lite" type="iri_lidar_lite" name="iri_lidar_lite" output="screen">
     <param name="serial_num"  type="string" value="A700evSl"/>
     <param name="config_mode" type="int"    value="0"/>
diff --git a/src/lidar_lite_driver_node.cpp b/src/lidar_lite_driver_node.cpp
index 3ab5695..426f222 100644
--- a/src/lidar_lite_driver_node.cpp
+++ b/src/lidar_lite_driver_node.cpp
@@ -7,15 +7,15 @@ LidarLiteDriverNode::LidarLiteDriverNode(ros::NodeHandle& nh)
   // , RunThread_(true)
   // , Thread_(boost::bind(&LidarLiteDriverNode::ThreadFunc, this))
 {
-  this->setRate(30);
+  this->setRate(100);
 
   // Read from launch file
   std::string serial;
   int config_mode;
-  this->public_node_handle_.param<std::string>("serial_num", serial,
-                                               "A700evSl");
-  this->public_node_handle_.param<int>("config_mode", config_mode, 0);
-  this->public_node_handle_.param<std::string>("frame_id", this->frame_id_,
+  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_,
                                                "lidar_lite");
 
   // Set device parameters
-- 
GitLab