Skip to content
Snippets Groups Projects
Commit 7d8d26b6 authored by Angel Santamaria-Navarro's avatar Angel Santamaria-Navarro
Browse files

Merge branch 'dev/fixes_updates_and_maintenance' into 'master'

Dev/fixes updates and maintenance

See merge request !1
parents 546a1dfb 5a464307
No related branches found
Tags v0.2
1 merge request!1Dev/fixes updates and maintenance
......@@ -40,6 +40,6 @@ gen = ParameterGenerator()
# Name Type Reconfiguration level Description Default Min Max
#gen.add("velocity_scale_factor", double_t, SensorLevels.RECONFIGURE_STOP, "Maximum velocity scale factor", 0.5, 0.0, 1.0)
gen.add("Config_mode", int_t, 0, "LidarLite configuration mode", 0, 1, 5)
gen.add("config_mode", int_t, 0, "LidarLite configuration mode", 0, 0, 5)
exit(gen.generate(PACKAGE, "LidarLiteDriver", "LidarLiteDriver"))
......@@ -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,10 +2,10 @@
<launch>
<node pkg="iri_lidar_lite" type="iri_lidar_lite" name="iri_lidar_lite" output="screen">
<node pkg="iri_lidar_lite_driver" type="iri_lidar_lite_driver" name="iri_lidar_lite_driver" output="screen">
<param name="serial_num" type="string" value="A700evSl"/>
<param name="config_mode" type="int" value="0"/>
<param name="frame_id" type="string" value="/kinton/lidarlite_link"/>
<param name="frame_id" type="string" value="/lidarlite_link"/>
<remap from="~range" to="kinton/lidarlite_range"/>
</node>
......
......@@ -66,7 +66,7 @@ LidarLiteDriver::config_update(Config& new_cfg, uint32_t level)
case iri_base_driver::RUNNING:
this->config_mode_ = new_cfg.Config_mode;
this->config_mode_ = new_cfg.config_mode;
try {
this->laser_ptr_->set_new_config(this->config_mode_);
......
......@@ -7,15 +7,16 @@ 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_,
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]
......
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