From bcc28b822bf2f7a0b5f658e4973bfac959a98466 Mon Sep 17 00:00:00 2001
From: Sergi Hernandez Juan <shernand@iri.upc.edu>
Date: Thu, 6 Sep 2018 18:03:14 +0200
Subject: [PATCH] Migration to the ROS Kinetic.

---
 CMakeLists.txt                     | 2 +-
 cfg/Bno055Imu.cfg                  | 4 ++--
 include/bno055_imu_ros_driver.h    | 4 ++--
 package.xml                        | 8 ++++----
 src/bno055_imu_ros_driver.cpp      | 9 ++++++---
 src/bno055_imu_ros_driver_node.cpp | 4 ++--
 6 files changed, 17 insertions(+), 14 deletions(-)

diff --git a/CMakeLists.txt b/CMakeLists.txt
index e1e039a..63c13ce 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -1,5 +1,5 @@
 cmake_minimum_required(VERSION 2.8.3)
-project(bno055_imu)
+project(iri_bno055_imu_driver)
 
 ## Find catkin macros and libraries
 find_package(catkin REQUIRED)
diff --git a/cfg/Bno055Imu.cfg b/cfg/Bno055Imu.cfg
index 5a4c162..bfce5cc 100755
--- a/cfg/Bno055Imu.cfg
+++ b/cfg/Bno055Imu.cfg
@@ -31,9 +31,9 @@
 
 # Author: 
 
-PACKAGE='bno055_imu'
+PACKAGE='iri_bno055_imu_driver'
 
-from driver_base.msg import SensorLevels
+from iri_base_driver.msg import SensorLevels
 from dynamic_reconfigure.parameter_generator_catkin import *
 
 gen = ParameterGenerator()
diff --git a/include/bno055_imu_ros_driver.h b/include/bno055_imu_ros_driver.h
index 934d6e2..56f33f9 100644
--- a/include/bno055_imu_ros_driver.h
+++ b/include/bno055_imu_ros_driver.h
@@ -26,7 +26,7 @@
 #define _bno055_imu_driver_h_
 
 #include <iri_base_driver/iri_base_driver.h>
-#include <bno055_imu/Bno055ImuConfig.h>
+#include <iri_bno055_imu_driver/Bno055ImuConfig.h>
 
 //include bno055_imu_driver main library
 #include "bno055_imu_driver.h"
@@ -64,7 +64,7 @@ class Bno055ImuDriver : public iri_base_driver::IriBaseDriver
     * Define a Config type with the Bno055ImuConfig. All driver implementations
     * will then use the same variable type Config.
     */
-    typedef bno055_imu::Bno055ImuConfig Config;
+    typedef iri_bno055_imu_driver::Bno055ImuConfig Config;
 
    /**
     * \brief config variable
diff --git a/package.xml b/package.xml
index 366fb2d..220a222 100644
--- a/package.xml
+++ b/package.xml
@@ -1,8 +1,8 @@
 <?xml version="1.0"?>
 <package>
-  <name>bno055_imu</name>
+  <name>iri_bno055_imu_driver</name>
   <version>0.0.0</version>
-  <description>The bno055_imu package</description>
+  <description>The iri_bno055_imu_driver package</description>
 
   <!-- One maintainer tag required, multiple allowed, one person per tag --> 
   <!-- Example:  -->
@@ -19,7 +19,7 @@
   <!-- Url tags are optional, but mutiple are allowed, one per tag -->
   <!-- Optional attribute type can be: website, bugtracker, or repository -->
   <!-- Example: -->
-  <!-- <url type="website">http://wiki.ros.org/bno055_imu</url> -->
+  <!-- <url type="website">http://wiki.ros.org/iri_bno055_imu_driver</url> -->
 
 
   <!-- Author tags are optional, mutiple are allowed, one per tag -->
@@ -51,4 +51,4 @@
     <!-- Other tools can request additional information be placed here -->
 
   </export>
-</package>
\ No newline at end of file
+</package>
diff --git a/src/bno055_imu_ros_driver.cpp b/src/bno055_imu_ros_driver.cpp
index 07d0a50..f550c85 100644
--- a/src/bno055_imu_ros_driver.cpp
+++ b/src/bno055_imu_ros_driver.cpp
@@ -19,6 +19,7 @@ bool Bno055ImuDriver::openDriver(void)
   try{
     this->imu_device=new CBNO055IMUDriver("BNO055_driver");
     this->imu_device->open(this->config_.serial_device);
+    ROS_INFO("IMU successfully opened");
     return true;
   }catch(CException &e){
     if(this->imu_device!=NULL)
@@ -50,6 +51,7 @@ bool Bno055ImuDriver::startDriver(void)
       this->imu_device->load_calibration(this->config_.cal_filename);
       this->imu_device->set_operation_mode(ndof_mode);
       this->imu_device->set_data_rate(this->config_.update_rate);
+      ROS_INFO("IMU successfully started");
       return true;
     }catch(CException &e){
       ROS_WARN_STREAM(e.what());
@@ -62,6 +64,7 @@ bool Bno055ImuDriver::startDriver(void)
       this->imu_device->set_operation_mode(config_mode);
       this->imu_device->set_data_rate(this->config_.update_rate);
       this->imu_device->set_operation_mode(ndof_mode);
+      ROS_INFO("IMU successfully stopped");
       return true;
     }catch(CException &e){
       ROS_WARN_STREAM(e.what());
@@ -84,14 +87,14 @@ void Bno055ImuDriver::config_update(Config& new_cfg, uint32_t level)
   // update driver with new_cfg data
   switch(this->getState())
   {
-    case Bno055ImuDriver::CLOSED:
+    case iri_base_driver::CLOSED:
       this->frame_id=new_cfg.tf_prefix+"/"+new_cfg.frame_id;
       break;
 
-    case Bno055ImuDriver::OPENED:
+    case iri_base_driver::OPENED:
       break;
 
-    case Bno055ImuDriver::RUNNING:
+    case iri_base_driver::RUNNING:
       break;
   }
 
diff --git a/src/bno055_imu_ros_driver_node.cpp b/src/bno055_imu_ros_driver_node.cpp
index de25be4..4db5265 100644
--- a/src/bno055_imu_ros_driver_node.cpp
+++ b/src/bno055_imu_ros_driver_node.cpp
@@ -7,7 +7,7 @@ Bno055ImuDriverNode::Bno055ImuDriverNode(ros::NodeHandle &nh) :
   unsigned int i;
 
   //init class attributes if necessary
-  this->loop_rate_ = 500;//in [Hz]
+  this->setRate(500);//in [Hz]
 
   // [init publishers]
   this->imu_publisher_ = this->public_node_handle_.advertise<sensor_msgs::Imu>("imu", 1);
@@ -117,5 +117,5 @@ Bno055ImuDriverNode::~Bno055ImuDriverNode(void)
 /* main function */
 int main(int argc,char *argv[])
 {
-  return driver_base::main<Bno055ImuDriverNode>(argc, argv, "bno055_imu_driver_node");
+  return iri_base_driver::main<Bno055ImuDriverNode>(argc, argv, "bno055_imu_driver_node");
 }
-- 
GitLab