[Documentation] [TitleIndex] [WordIndex

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.

Honeywell HGuide Web Page

ROS Driver Download

Honeywell IMU GitLab

please not that you have to have a GitLab account and request access to the Honeywell IMU Group

The hg_node includes:

Functions Description

serial_publisher

rosrun command:

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

Defaults:

Program is used to publish translated IMU data for other nodes to use. Separate Control, Inertial and Health messages are sent. The program will determine the IMU used and publish the messages accordingly. Furthermore standard sensor_msgs::Imu message is being published for both var

HG1120 - messages are common for both output variants (0x04/0x05 and 0x0C/0x0D)

<hg_node::X04ControlMessage>”HG1120/ControlData”
<hg_node::X05InertialMessage>”HG1120/InertialData”
<hg_node::X04HealthData>”HG1120/HealthData”
<sensor_msgs::Imu>"HG1120/ImuData"

HG4930

<hg_node::X01ControlMessage>”HG4930/ControlData”
<hg_node::X02InertialMessage>”HG4930/InertialData”
<hg_node::X01HealthData>”HG4930/HealthData”
<sensor_msgs::Imu>"HG4930/ImuData"

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 published “HG1120/ImuData” or “HG4930/ImuData” topics and use 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.

Quick Start

Prerequisites:

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 with default 1,000,000 baudrate 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

Message Types Definition

For definition of the sensor_msgs::Imu, please see official documentation.

In order to use driver's custom messages in your c/c++ code, use:

HG1120

#include <hg_node/X04ControlMessage.h>
#include <hg_node/X04HealthData.h>
#include <hg_node/X05InertialMessage.h>

Inertial Message <hg_node::X05InertialMessage>

Data type

Name

Description

uint8

IMUAddress

IMU Address (0x0E)

uint8

MessageID

Message ID (0x05, 0x0D)

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::X04ControlMessage>

Data Type

Name

Description

uint8

IMUAddress

IMU Address (0x0E)

uint8

MessageID

Message ID (0x04, 0x0C)

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:: X04HealthData>

Data Type

Name

Description

uint8

IMUAddress

IMU Address (0x0E)

uint8

MessageID

Message ID (0x04, 0x0C)

uint8

MultiplexedCounter

MUX status word counter

bool

IMUOK

0 = OK; 1 = Fail

bool

SensorBoardInitializationSuccessful

0 = OK; 1 = Fail

bool

AccelerometerXValidity

0 = OK; 1 = Fail

bool

AccelerometerYValidity

0 = OK; 1 = Fail

bool

AccelerometerZValidity

0 = OK; 1 = Fail

bool

GyroXValidity

0 = OK; 1 = Fail

bool

GyroYValidity

0 = OK; 1 = Fail

bool

GyroZValidity

0 = OK; 1 = Fail

bool

MagnetometerValidity

0 = OK; 1 = Fail

bool

PowerUpBITStatus

0 = OK; 1 = Fail

bool

ContinuousBITStatus

0 = OK; 1 = Fail

bool

PowerUpTest

0 = OK; 1 = Fail

int8

SoftwareVersionNumber

IMU Software version

float32

AccelerometerGyroSensorTemperature

Accel/Gyro Temperature (°C)

float32

MagnetometerTemperature

Magnetometer Temperature (°C)

bool

DIO1, DIO2, DIO3, DIO4

IMU Startup conf. bits

uint16

Checksum

Message checksum

HG4930

#include <hg_node/X01ControlMessage.h>
#include <hg_node/X01HealthData.h>
#include <hg_node/X02InertialMessage.h>

Control Message <hg_node::X02InertialMessage>

Data type

Name

Description

uint8

IMUAddress

IMU Address (0x0E)

uint8

MessageID

Message ID (0x02)

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::X01ControlMessage>

Data Type

Name

Description

uint8

IMUAddress

IMU Address (0x0E)

uint8

MessageID

Message ID (0x01)

float32[3]

AngularRate

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

float32[3]

LinearAcceleration

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

Health Message <hg_node:: X01HealthData>

Data Type

Name

Description

uint8

IMUAddress

IMU Address (0x0E)

uint8

MessageID

Message ID (0x01)

uint8

MultiplexedCounter

MUX status word counter

bool

IMU

0 = OK; 1 = Fail

bool

Gyro

0 = OK; 1 = Fail

bool

Accelerometer

0 = OK; 1 = Fail

bool

AccelerometerYValidity

0 = OK; 1 = Fail

bool

AccelerometerZValidity

0 = OK; 1 = Fail

bool

GyroOK

0 = OK; 1 = Fail

bool

GyroXValidity

0 = OK; 1 = Fail [inverted from ICD]

bool

GyroYValidity

0 = OK; 1 = Fail [inverted from ICD]

bool

GyroZValidity

0 = OK; 1 = Fail [inverted from ICD]

bool

IMUOK

0 = OK; 1 = Fail

uint8

StatusWord2A2BFlag

Indicator which status word is being sent [0 = 2A | 1 = 2B]

int8

SoftwareVersionNumber

IMU Software version

int8

Temperature

IMU Temperature (°C)

bool

GyroHealth

0 = OK; 1 = Fail

bool

StartDataFlag

0 = OK; 1 = Fail

bool

ProcessTest

0 = OK; 1 = Fail

bool

MemoryTest

0 = OK; 1 = Fail

bool

ElectronicsTest

0 = OK; 1 = Fail

bool

GyroHealth2

0 = OK; 1 = Fail

bool

AccelerometerHealth

0 = OK; 1 = Fail

uint16

Checksum

Message checksum

Report a Bug

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


2022-05-28 12:38