Skip to content
Snippets Groups Projects
Commit 5a85592a authored by asantamaria's avatar asantamaria
Browse files

Update code according with new driver naming convention

parent 546a1dfb
No related branches found
No related tags found
1 merge request!1Dev/fixes updates and maintenance
......@@ -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
......
......@@ -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"/>
......
......@@ -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
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment