Forráskód Böngészése

新增串口读取imu模块代码

corvin 5 éve
szülő
commit
ccdaaac447

+ 1 - 0
src/rasp_imu_hat_6dof/rasp_imu_hat_6dof/nodes/imu_data.py

@@ -11,6 +11,7 @@
 #    20191209: Add get imu chip temperature function-get_temp().
 
 import smbus
+import rospy
 import numpy as np
 
 class MyIMU(object):

+ 206 - 0
src/rasp_imu_hat_6dof/serial_imu_hat_6dof/CMakeLists.txt

@@ -0,0 +1,206 @@
+cmake_minimum_required(VERSION 2.8.3)
+project(serial_imu_hat_6dof)
+
+## Compile as C++11, supported in ROS Kinetic and newer
+# add_compile_options(-std=c++11)
+
+## Find catkin macros and libraries
+## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
+## is used, also find other catkin packages
+find_package(catkin REQUIRED COMPONENTS
+  dynamic_reconfigure
+  roscpp
+  sensor_msgs
+)
+
+## System dependencies are found with CMake's conventions
+# find_package(Boost REQUIRED COMPONENTS system)
+
+
+## Uncomment this if the package has a setup.py. This macro ensures
+## modules and global scripts declared therein get installed
+## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
+# catkin_python_setup()
+
+################################################
+## Declare ROS messages, services and actions ##
+################################################
+
+## To declare and build messages, services or actions from within this
+## package, follow these steps:
+## * Let MSG_DEP_SET be the set of packages whose message types you use in
+##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
+## * In the file package.xml:
+##   * add a build_depend tag for "message_generation"
+##   * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
+##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in
+##     but can be declared for certainty nonetheless:
+##     * add a exec_depend tag for "message_runtime"
+## * In this file (CMakeLists.txt):
+##   * add "message_generation" and every package in MSG_DEP_SET to
+##     find_package(catkin REQUIRED COMPONENTS ...)
+##   * add "message_runtime" and every package in MSG_DEP_SET to
+##     catkin_package(CATKIN_DEPENDS ...)
+##   * uncomment the add_*_files sections below as needed
+##     and list every .msg/.srv/.action file to be processed
+##   * uncomment the generate_messages entry below
+##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
+
+## Generate messages in the 'msg' folder
+# add_message_files(
+#   FILES
+#   Message1.msg
+#   Message2.msg
+# )
+
+## Generate services in the 'srv' folder
+# add_service_files(
+#   FILES
+#   Service1.srv
+#   Service2.srv
+# )
+
+## Generate actions in the 'action' folder
+# add_action_files(
+#   FILES
+#   Action1.action
+#   Action2.action
+# )
+
+## Generate added messages and services with any dependencies listed here
+# generate_messages(
+#   DEPENDENCIES
+#   sensor_msgs
+# )
+
+################################################
+## Declare ROS dynamic reconfigure parameters ##
+################################################
+
+## To declare and build dynamic reconfigure parameters within this
+## package, follow these steps:
+## * In the file package.xml:
+##   * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
+## * In this file (CMakeLists.txt):
+##   * add "dynamic_reconfigure" to
+##     find_package(catkin REQUIRED COMPONENTS ...)
+##   * uncomment the "generate_dynamic_reconfigure_options" section below
+##     and list every .cfg file to be processed
+
+## Generate dynamic reconfigure parameters in the 'cfg' folder
+# generate_dynamic_reconfigure_options(
+#   cfg/DynReconf1.cfg
+#   cfg/DynReconf2.cfg
+# )
+
+###################################
+## catkin specific configuration ##
+###################################
+## The catkin_package macro generates cmake config files for your package
+## Declare things to be passed to dependent projects
+## INCLUDE_DIRS: uncomment this if your package contains header files
+## LIBRARIES: libraries you create in this project that dependent projects also need
+## CATKIN_DEPENDS: catkin_packages dependent projects also need
+## DEPENDS: system dependencies of this project that dependent projects also need
+catkin_package(
+#  INCLUDE_DIRS include
+#  LIBRARIES serial_imu_hat_6dof
+#  CATKIN_DEPENDS dynamic_reconfigure roscpp sensor_msgs
+#  DEPENDS system_lib
+)
+
+###########
+## Build ##
+###########
+
+## Specify additional locations of header files
+## Your package locations should be listed before other locations
+include_directories(
+# include
+  ${catkin_INCLUDE_DIRS}
+)
+
+## Declare a C++ library
+# add_library(${PROJECT_NAME}
+#   src/${PROJECT_NAME}/serial_imu_hat_6dof.cpp
+# )
+
+## Add cmake target dependencies of the library
+## as an example, code may need to be generated before libraries
+## either from message generation or dynamic reconfigure
+# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
+
+## Declare a C++ executable
+## With catkin_make all packages are built within a single CMake context
+## The recommended prefix ensures that target names across packages don't collide
+# add_executable(${PROJECT_NAME}_node src/serial_imu_hat_6dof_node.cpp)
+
+## Rename C++ executable without prefix
+## The above recommended prefix causes long target names, the following renames the
+## target back to the shorter version for ease of user use
+## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
+# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
+
+## Add cmake target dependencies of the executable
+## same as for the library above
+# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
+
+## Specify libraries to link a library or executable target against
+# target_link_libraries(${PROJECT_NAME}_node
+#   ${catkin_LIBRARIES}
+# )
+
+#############
+## Install ##
+#############
+
+# all install targets should use catkin DESTINATION variables
+# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
+
+## Mark executable scripts (Python etc.) for installation
+## in contrast to setup.py, you can choose the destination
+# install(PROGRAMS
+#   scripts/my_python_script
+#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
+# )
+
+## Mark executables for installation
+## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
+# install(TARGETS ${PROJECT_NAME}_node
+#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
+# )
+
+## Mark libraries for installation
+## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
+# install(TARGETS ${PROJECT_NAME}
+#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+#   RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
+# )
+
+## Mark cpp header files for installation
+# install(DIRECTORY include/${PROJECT_NAME}/
+#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
+#   FILES_MATCHING PATTERN "*.h"
+#   PATTERN ".svn" EXCLUDE
+# )
+
+## Mark other files for installation (e.g. launch and bag files, etc.)
+# install(FILES
+#   # myfile1
+#   # myfile2
+#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
+# )
+
+#############
+## Testing ##
+#############
+
+## Add gtest based cpp test target and link libraries
+# catkin_add_gtest(${PROJECT_NAME}-test test/test_serial_imu_hat_6dof.cpp)
+# if(TARGET ${PROJECT_NAME}-test)
+#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
+# endif()
+
+## Add folders to be run by python nosetests
+# catkin_add_nosetests(test)

+ 46 - 0
src/rasp_imu_hat_6dof/serial_imu_hat_6dof/include/imu_data.h

@@ -0,0 +1,46 @@
+#ifndef _IMU_DATA_H_
+#define _IMU_DATA_H_
+
+#define ACC_X_REG  0x34
+#define ACC_Y_REG  0x35
+#define ACC_Z_REG  0x36
+
+#define GYO_X_REG  0x37
+#define GYO_Y_REG  0x38
+#define GYO_Z_REG  0x39
+
+#define ROLL_REG   0x3d
+#define PITCH_REG  0x3e
+#define YAW_REG    0x3f
+
+class myIMU
+{
+    public:
+        float getRollData();
+        float getPitchData();
+        float getYawData();
+
+        float getAccXData();
+        float getAccYData();
+        float getAccZData();
+
+        float getGyoXData();
+        float getGyoYData();
+        float getGyoZData();
+
+    private:
+        unsigned char accX[2];
+        unsigned char accY[2];
+        unsigned char accZ[2];
+
+        unsigned char gyoX[2];
+        unsigned char gyoY[2];
+        unsigned char gyoZ[2];
+
+        unsigned char roll[2];
+        unsigned char pitch[2];
+        unsigned char yaw[2];
+};
+
+#endif
+

+ 68 - 0
src/rasp_imu_hat_6dof/serial_imu_hat_6dof/package.xml

@@ -0,0 +1,68 @@
+<?xml version="1.0"?>
+<package format="2">
+  <name>serial_imu_hat_6dof</name>
+  <version>0.0.0</version>
+  <description>The serial_imu_hat_6dof package</description>
+
+  <!-- One maintainer tag required, multiple allowed, one person per tag -->
+  <!-- Example:  -->
+  <!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
+  <maintainer email="corvin_zhang@corvin.cn">corvin</maintainer>
+
+
+  <!-- One license tag required, multiple allowed, one license per tag -->
+  <!-- Commonly used license strings: -->
+  <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
+  <license>TODO</license>
+
+
+  <!-- Url tags are optional, but multiple are allowed, one per tag -->
+  <!-- Optional attribute type can be: website, bugtracker, or repository -->
+  <!-- Example: -->
+  <!-- <url type="website">http://wiki.ros.org/serial_imu_hat_6dof</url> -->
+
+
+  <!-- Author tags are optional, multiple are allowed, one per tag -->
+  <!-- Authors do not have to be maintainers, but could be -->
+  <!-- Example: -->
+  <!-- <author email="jane.doe@example.com">Jane Doe</author> -->
+
+
+  <!-- The *depend tags are used to specify dependencies -->
+  <!-- Dependencies can be catkin packages or system dependencies -->
+  <!-- Examples: -->
+  <!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
+  <!--   <depend>roscpp</depend> -->
+  <!--   Note that this is equivalent to the following: -->
+  <!--   <build_depend>roscpp</build_depend> -->
+  <!--   <exec_depend>roscpp</exec_depend> -->
+  <!-- Use build_depend for packages you need at compile time: -->
+  <!--   <build_depend>message_generation</build_depend> -->
+  <!-- Use build_export_depend for packages you need in order to build against this package: -->
+  <!--   <build_export_depend>message_generation</build_export_depend> -->
+  <!-- Use buildtool_depend for build tool packages: -->
+  <!--   <buildtool_depend>catkin</buildtool_depend> -->
+  <!-- Use exec_depend for packages you need at runtime: -->
+  <!--   <exec_depend>message_runtime</exec_depend> -->
+  <!-- Use test_depend for packages you need only for testing: -->
+  <!--   <test_depend>gtest</test_depend> -->
+  <!-- Use doc_depend for packages you need only for building documentation: -->
+  <!--   <doc_depend>doxygen</doc_depend> -->
+  <buildtool_depend>catkin</buildtool_depend>
+  <build_depend>dynamic_reconfigure</build_depend>
+  <build_depend>roscpp</build_depend>
+  <build_depend>sensor_msgs</build_depend>
+  <build_export_depend>dynamic_reconfigure</build_export_depend>
+  <build_export_depend>roscpp</build_export_depend>
+  <build_export_depend>sensor_msgs</build_export_depend>
+  <exec_depend>dynamic_reconfigure</exec_depend>
+  <exec_depend>roscpp</exec_depend>
+  <exec_depend>sensor_msgs</exec_depend>
+
+
+  <!-- The export tag contains other, unspecified, tags -->
+  <export>
+    <!-- Other tools can request additional information be placed here -->
+
+  </export>
+</package>

+ 303 - 0
src/rasp_imu_hat_6dof/serial_imu_hat_6dof/src/proc_serial_data.cpp

@@ -0,0 +1,303 @@
+/*************************************************************************
+ * Copyright:2016-2020 www.corvin.cn ROS小课堂
+ * Description:使用串口方式读取IMU模块信息.
+ * Author: corvin
+ * History:
+ *   20200401:init this file.
+ *************************************************************************/
+#include<stdio.h>
+#include<stdlib.h>
+#include<fcntl.h>
+#include<unistd.h>
+#include<assert.h>
+#include<termios.h>
+#include<string.h>
+#include<sys/time.h>
+#include<sys/types.h>
+#include<errno.h>
+
+
+#define  BAUD  9600 //9600 default baund for JY61P
+
+/**********************************************
+ * Description:打开串口,输入设备号参数即可.
+ *********************************************/
+int open_serialPort(const char *path)
+{
+    int fd = open(path, O_RDWR|O_NOCTTY);
+    if (-1 == fd)
+    {
+        return(-1);
+    }
+
+    if(isatty(STDIN_FILENO) == 0)
+    {
+        return(-2);
+    }
+    else
+    {
+        return fd;
+    }
+}
+
+/************************************************************************
+ * Description:配置可以与串口进行正常数据通信的参数.
+ ***********************************************************************/
+int set_serialPort(int fd, int baud, int dataBits, char parity, int stopBits)
+{
+    struct termios terminfo;
+    bzero(&terminfo, sizeof(terminfo));
+
+    /*设置串口通信波特率-bps*/
+    switch(baud)
+    {
+        case 9600:
+           cfsetispeed(&terminfo, B9600); //设置输入速度
+           cfsetospeed(&terminfo, B9600); //设置输出速度
+           break;
+
+        case 19200:
+           cfsetispeed(&terminfo, B19200);
+           cfsetospeed(&terminfo, B19200);
+           break;
+
+        case 38400:
+           cfsetispeed(&terminfo, B38400);
+           cfsetospeed(&terminfo, B38400);
+           break;
+
+        case 57600:
+           cfsetispeed(&terminfo, B57600);
+           cfsetospeed(&terminfo, B57600);
+           break;
+
+       case 115200:
+           cfsetispeed(&terminfo, B115200);
+           cfsetospeed(&terminfo, B115200);
+           break;
+
+       default://设置默认波特率9600
+           cfsetispeed(&terminfo, B9600);
+           cfsetospeed(&terminfo, B9600);
+           break;
+    }
+
+    //设置数据位
+    terminfo.c_cflag |= CLOCAL|CREAD;
+    terminfo.c_cflag &= ~CSIZE;
+    switch(dataBits)
+    {
+        case 7:
+           terminfo.c_cflag |= CS7;
+           break;
+
+        case 8:
+           terminfo.c_cflag |= CS8;
+           break;
+
+        default:
+           printf("Set dataBits error !\n");
+           return -1;
+    }
+
+    //设置奇偶校验位
+    switch(parity)
+    {
+        case 'o': //设置奇校验
+        case 'O':
+           terminfo.c_cflag |= PARENB;
+           terminfo.c_cflag |= PARODD;
+           terminfo.c_iflag |= (INPCK|ISTRIP);
+           break;
+
+        case 'e': //设置偶校验
+        case 'E':
+           terminfo.c_iflag |= (INPCK|ISTRIP);
+           terminfo.c_cflag |= PARENB;
+           terminfo.c_cflag &= ~PARODD;
+           break;
+
+        case 'n': //不设置奇偶校验位
+        case 'N':
+           terminfo.c_cflag &= ~PARENB;
+           break;
+
+        default:
+          printf("set parity error !\n");
+          return -2;
+    }
+
+    //设置停止位
+    switch(stopBits)
+    {
+        case 1:
+            terminfo.c_cflag &= ~CSTOPB;
+            break;
+
+        case 2:
+            terminfo.c_cflag |= CSTOPB;
+            break;
+
+        default:
+            printf("set stopBits error !\n");
+            return -3;
+    }
+
+    terminfo.c_cc[VTIME] = 10;
+    terminfo.c_cc[VMIN]  = 0;
+    tcflush(fd, TCIFLUSH);
+
+    if((tcsetattr(fd, TCSANOW, &terminfo)) != 0)
+    {
+      printf("config serialPort params error !\n");
+      return -4;
+    }
+
+    return 0;
+}
+
+/**************************************
+ * Description:关闭串口文件描述符.
+ *************************************/
+int close_serialPort(int fd)
+{
+    int ret = close(fd);
+    return ret;
+}
+
+/*****************************************************
+ * Description:向串口中发送数据.
+ ****************************************************/
+int send_data(int fd, char *send_buffer, int length)
+{
+	length = write(fd, send_buffer, length*sizeof(unsigned char));
+
+	return length;
+}
+
+/*******************************************************
+ * Description:从串口中接收数据.
+ *******************************************************/
+int recv_data(int fd, char* recv_buffer, int len)
+{
+    int length = read(fd, recv_buffer, len);
+    return length;
+}
+
+float a[3], w[3], Angle[3], q[4];
+/************************************************************
+ * Description:根据串口数据协议来解析有效数据,
+ ***********************************************************/
+void parse_serialData(char chr)
+{
+    static char chrBuf[100];
+    static unsigned char chrCnt = 0;
+    signed short sData[4]; //存储8字节的有效信息
+    unsigned char i = 0;
+    char frameSum = 0;
+
+    chrBuf[chrCnt++] = chr; //保存当前字节,字节计数加1
+
+    //判断是否满一个完整数据帧11个字节
+    if(chrCnt < 11)
+        return;
+
+    //计算数据帧的前十个字节的校验和
+    for(i=0; i<10; i++)
+    {
+        frameSum += chrBuf[i];
+    }
+
+    //找到数据帧第一个字节是0x55,校验和是否正确,若两者有一个不正确,
+    //都需要移动到最开始的字节,再读取新的字节进行判断数据帧完整性
+    if ((chrBuf[0] != 0x55)||(frameSum != chrBuf[10]))
+    {
+        memcpy(&chrBuf[0], &chrBuf[1], 10); //将有效数据往前移动1字节位置
+        chrCnt--; //字节计数减1,需要再多读取一个字节进来,重新判断数据帧
+        return;
+    }
+
+    memcpy(&sData[0], &chrBuf[2], 8);
+    switch(chrBuf[1])
+    {
+        case 0x51: //加速度输出
+            for(i=0; i<3; i++)
+            {
+                a[i] = (float)sData[i]/32768.0*16.0;
+            }
+            printf("a:%6.4f %6.4f %6.4f ", a[0], a[1], a[2]);
+            break;
+
+        case 0x52: //角速度输出
+            for(i=0; i<3; i++)
+            {
+                w[i] = (float)sData[i]/32768.0*2000.0;
+            }
+            printf("w:%7.4f %7.4f %7.4f ", w[0], w[1], w[2]);
+            break;
+
+        case 0x53: //角度输出, roll, pitch, yaw
+            for (i=0; i<3; i++)
+            {
+                Angle[i] = (float)sData[i]/32768.0*180.0;
+            }
+            printf("A:%7.4f %7.4f %7.4f ", Angle[0], Angle[1], Angle[2]);
+            break;
+
+        case 0x59: //四元素输出
+            for (i=0; i<4; i++)
+            {
+                q[i] = (float)sData[i]/32768.0;
+            }
+            printf("q:%6.4f %6.4f %6.4f %6.4f\n", q[0], q[1], q[2], q[3]);
+            break;
+    }
+    chrCnt = 0;
+}
+
+int main(void)
+{
+    int ret = 0;
+    int port_fd = 0;
+    char r_buf[512];
+    bzero(r_buf, 512);
+
+    port_fd = open_serialPort("/dev/ttyUSB0");
+    if(port_fd < 0)
+    {
+        printf("open_serialPort error !\n");
+        exit(EXIT_FAILURE);
+    }
+
+    if(set_serialPort(port_fd, BAUD, 8, 'N', 1) < 0)
+    {
+        printf("set serialPort failed !\n");
+        exit(EXIT_FAILURE);
+    }
+
+    while(1)
+    {
+        ret = recv_data(port_fd, r_buf,  44);
+        if(ret == -1)
+        {
+            printf("read serial port data failed !\n");
+            exit(EXIT_FAILURE);
+        }
+
+        for (int i=0; i<ret; i++)
+        {
+            parse_serialData(r_buf[i]);
+        }
+        usleep(1000);
+    }
+
+    ret = close_serialPort(port_fd);
+    if(ret == -1)
+    {
+        printf("close serialPort error !\n");
+        exit(EXIT_FAILURE);
+    }
+
+    exit(EXIT_SUCCESS);
+}
+

+ 73 - 0
src/rasp_imu_hat_6dof/serial_imu_hat_6dof/src/serial_imu_node.cpp

@@ -0,0 +1,73 @@
+#include <ros/ros.h>
+#include "imu_data.h"
+#include <Eigen/Eigen>
+#include <Eigen/Geometry>
+#include <Eigen/Core>
+#include <sensor_msgs/Imu.h>
+
+
+Eigen::Quaterniond euler2Quater(float roll, float yaw, float pitch)
+{
+    Eigen::AngleAxisd rollAngle(roll, Eigen::Vector3d::UnitZ());
+    Eigen::AngleAxisd yawAngle(yaw, Eigen::Vector3d::UnitY());
+    Eigen::AngleAxisd pitchAngle(pitch, Eigen::Vector3d::UnitX());
+
+    Eigen::Quaterniond q = rollAngle * yawAngle * pitchAngle;
+    cout << "Euler2Quaternion result is:" <<endl;
+    cout << "x = " << q.x() <<endl;
+    cout << "y = " << q.y() <<endl;
+    cout << "z = " << q.z() <<endl;
+    cout << "w = " << q.w() <<endl<<endl;
+
+    return q;
+}
+
+int main(int argc, char **argv)
+{
+    ros::init(argc, argv, "imu_data_pub_node");
+    ros::NodeHandle handle;
+
+    ros::Publisher imu_pub = handle.advertise<sensor_msgs::Imu>("imu_data", 2);
+    ros::Rate loop_rate(10);
+    sensor_msgs::Imu imu_msg;
+    float yaw_tmp,pitch_tmp,roll_tmp;
+
+    while(ros::ok())
+    {
+        imu_msg.header.stamp = ros::Time::now();
+        imu_msg.header.frame_id = "base_link";
+
+        roll_tmp  = my_imu.getRollData();
+        pitch_tmp = my_imu.getPitchData();
+        yaw_tmp   = my_imu.getYawData();
+
+        Eigen::Quaterniond q = euler2Quater(roll_tmp, pitch_tmp, yaw_tmp);
+        imu_msg.orientation.x = q.x();
+        imu_msg.orientation.y = q.y();
+        imu_msg.orientation.z = q.z();
+        imu_msg.orientation.w = q.w();
+        imu_msg.orientation_covariance = {0.0025, 0, 0,
+                                          0, 0.0025, 0,
+                                          0, 0, 0.0025};
+
+        imu_msg.angular_velocity.x = my_imu.getGyoXData();
+        imu_msg.angular_velocity.y = my_imu.getGyoYData();
+        imu_msg.angular_velocity.z = my_imu.getGyoZData();
+        imu_msg.angular_velocity_covariance = {0.02, 0, 0,
+                                               0, 0.02, 0,
+                                               0, 0, 0.02};
+
+        imu_msg.linear_acceleration.x = my_imu.getAccXData();
+        imu_msg.linear_acceleration.y = my_imu.getAccYData();
+        imu_msg.linear_acceleration.z = my_imu.getAccZData();
+        imu_msg.linear_acceleration_covariance = {0.04, 0, 0,
+                                                   0, 0.04, 0,
+                                                   0, 0, 0.04};
+
+        imu_pub.publish(imu_msg);
+        ros::spinOnce();
+        loop_rate.sleep();
+    }
+
+    return 0;
+}