Honeywell IMU - hg_node

The purpose of the hg_node is to translate the received buffer into human readable data and publish it to the ROS for other nodes to use


Currently the HG1120 and HG4930 IMUs are supported.


The driver was designed with ROS Kinetic distribution and might not work for others without modifications.

ROS Driver Download

Honeywell IMU GitLab

The hg_node includes:

  • API - HgDataParser

  • Publisher - serial_publisher
  • Example - listener_example

Functions Description

serial_publisher

rosrun command:

(su) $ rosrun hg_node serial_publisher [optional port name]

Default port name = /dev/ttyUSB0

Program is used to publish translated IMU data for other nodes to use. Separate Control, Inertial and Health messages are sent.

<hg_node::CtrData> ”hgControlData”
<hg_node::IneData> ”hgInertialData”
<hg_node::HealthData> ”hgHealthData”

Super user access is required to access the com port. Without it, the publisher won’t be able to open it and will return -1 value.

listener_example

rosrun command:

$ rosrun hg_node listener_example

Program is used as an example to show how to subscribe to “hgControlData” and “hgInertialData” topics and publish them in turtlesim specific “cmd_vel” defining the angular and forward speed of the turtle.

Note that the axes were changed in order to work better with the evaluation board and that the turtle is limited to yaw rotation and forward/backward movement.

Message Types Definition

In order to use the messages in your c/c++ code, use:

#include <hg_node/CtrMsg.h>
#include <hg_node/IneMsg.h>
#include <hg_node/HealthMsg.h>

Inertial Message <hg_node::IneData>

Data type

Name

Description

uint8

IMUAddress

IMU Address (0x0E)

uint8

MessageID

Message ID (0x01, 0x04, 0x0C)

float32[3]

DeltaAngle

Change in attitude since last inertial message [x, y, z] (rad)

float32[3]

DeltaVelocity

Change in velocity since last inertial message [x, y, z] (m/s)

Control Message <hg_node:: CtrData>

Data Type

Name

Description

uint8

IMUAddress

IMU Address (0x0E)

uint8

MessageID

Message ID (0x02, 0x05, 0x0D)

float32[3]

AngularRate

Angular Rate values [x, y, z] (rad/s)

float32[3]

LinearAcceleration

Linear Acceleration values [x, y, z] (m/s2)

float32[3]

MagField

Magnetic field values [x, y, z] (mgauss)

Health Message <hg_node:: HealthData>

Data Type

Name

Description

uint8

IMUAddress

IMU Address (0x0E)

uint8

MessageID

Message ID (0x02, 0x05, 0x0D)

bool

IMUOK

0 = OK; 1 = Fail

bool

AccelOK

0 = OK; 1 = Fail

bool

GyroOK

0 = OK; 1 = Fail

bool

GyroXValidity

0 = OK; 1 = Fail

bool

GyroYValidity

0 = OK; 1 = Fail

bool

GyroZValidity

0 = OK; 1 = Fail

float32

Temperature

IMU Temperature (°C)

uint16

Checksum

Message checksum

Quick Start

Prerequisites:

  • ROS Kinetic running
  • IMU connected over USB-serial to ROS device

1. Copy “hg_node” folder into ~/catkin_ws/src/

2. Open terminal to start roscore

$ roscore

3. Open another terminal and change directory to /catkin_ws/

$ cd ~/catkin_ws/

4. Elevate privileges to super user

$ sudo su

5. Source catkin under super user

$ source ./devel/setup.bash

6. Build the package

$ catkin_make

7. Start the launch file

$ roslaunch hg_node TurtleExample.launch

The launch file will open serial communication over default /dev/ttyUSB0 port and stream the data to turtle sim for you to test the device function

API Description

It is used to translate the UINT8 buffered data to container structures for easier handling.

Separate data structures for HG4930 and HG1120 are used as, both devices provide slightly different data.

Used units

Variable Name

Symbol

Unit

DeltaAngle

rad

radians

DeltaVelocity

m/s

meters per second

AngularRate

rad/s

radians per second

LinearAcceleration

m/s2

meters per second squared

MagField

mgauss

miligauss

Temperature

°C

degrees centigrade

Report a Bug

Please feel free to post bug reports and suggestions on the GitLab

Wiki: hg_node (last edited 2018-08-10 15:19:27 by CtiborMazal)