[Documentation] [TitleIndex] [WordIndex

Honeywell INS - hg_nav_node

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


Currently the HGuide n580 INS is 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_nav_node includes:

Functions Description

serial_publisher_nav

rosrun command:

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

Defaults:

Program is used to publish translated INS data for other nodes to use. Each message output is published separately as well as INS Status info published in multiple messages.

<hg_nav_node::InsGnssBit>                       “hgINS/Output/InsGnssBit”
<hg_nav_node::AckOutput>                        “hgINS/Output/AckData”
<hg_nav_node::ConfigurationOutput>              “hgINS/Output/Configuration”
<hg_nav_node::EulerAttitudeOutput>              “hgINS/Output/EulerAttitude”
<hg_nav_node::GeodeticPosition>                 “hgINS/Output/GeodeticPosition”
<hg_nav_node::GnssPositionOutput>               “hgINS/Output/GnssPosition”
<hg_nav_node::GnssAttitudeOutput>               “hgINS/Output/GnssAttitude”
<hg_nav_node::InertialOutput>                   “hgINS/Output/InertialData”
<hg_nav_node::NavigationOutput>                 “hgINS/Output/NavigationData”
<hg_nav_node::NEDVelocityOutput>                “hgINS/Output/NEDVelocity”
<hg_nav_node::StatusOutput>                     “hgINS/Output/Status”
<hg_nav_node::TimeMarkOutput>                   “hgINS/Output/TimeMark”
<hg_nav_node::MotionDetectionOutput>            “hgINS/Output/MotionDetection”
<hg_nav_node::AntennaLeverArmsEstimatesOutput>  “hgINS/Output/AntennaLeverArmsEstimates”
<hg_nav_node::OdometerCalibrationOutput>        “hgINS/Output/OdometerCalibration”

The publisher is handling device input as well. It leverages defined input messages and subscribes to predefined topics as shown bellow. The listener_example_nav is demonstrating how to use this to configure unit.

<hg_nav_node::AntLeverArmsInput>                “hgINS/Input/AntennaLeverArms”
<hg_nav_node::BaroAltInput>                     “hgINS/Input/BarometricAltitude”
<hg_nav_node::ConfigInput>                      “hgINS/Input/Configuration”
<hg_nav_node::MagHeadingInput>                  “hgINS/Input/MagneticHeading”
<hg_nav_node::MsgSetInput>                      “hgINS/Input/EnableMessages”
<hg_nav_node::NavInput>                         “hgINS/Input/NavigationInput”
<hg_nav_node::NavModeInput>                     “hgINS/Input/NavigationMode”
<hg_nav_node::VehicleFrameInput>                “hgINS/Input/VehicleFrame”
<hg_nav_node::OdometerConfigInput>              “hgINS/Input/OdometerConfiguration”

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_nav

rosrun command:

$ rosrun hg_node listener_example_nav

Program is used as an example to show how to set INS to send inertial data and subscribe to “hgInertialData” topic 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, simply use to include the full suite:

#include "api_to_topics.h"

or you can address the messages individually:

//Input Messages
#include <hg_nav_node/AntLeverArmsInput.h>
#include <hg_nav_node/BaroAltInput.h>
#include <hg_nav_node/MagHeadingInput.h>
#include <hg_nav_node/ConfigInput.h>
#include <hg_nav_node/MsgSetInput.h>
#include <hg_nav_node/NavInput.h>
#include <hg_nav_node/NavModeInput.h>
#include <hg_nav_node/VehicleFrameInput.h>
#include <hg_nav_node/VelocityAidingInput.h>
#include <hg_nav_node/OdometerConfigInput.h>

//Output Messages
#include <hg_nav_node/AckOutput.h>
#include <hg_nav_node/ConfigurationOutput.h>
#include <hg_nav_node/EulerAttitudeOutput.h>
#include <hg_nav_node/GeodeticPositionOutput.h>
#include <hg_nav_node/GnssAttitudeOutput.h>
#include <hg_nav_node/GnssPositionOutput.h>
#include <hg_nav_node/InertialOutput.h>
#include <hg_nav_node/InsGnssBit.h>
#include <hg_nav_node/NavigationOutput.h>
#include <hg_nav_node/NEDVelocityOutput.h>
#include <hg_nav_node/StatusOutput.h>
#include <hg_nav_node/TimeMarkOutput.h>
#include <hg_nav_node/DistanceTraveledOutput.h>
#include <hg_nav_node/MotionDetectionOutput.h>
#include <hg_nav_node/AntennaLeverArmsEstimatesOutput.h>
#include <hg_nav_node/OdometerCalibrationOutput.h>

The driver is also outputting a suite of standard messages

<sensor_msgs::Imu> “hgINS/Std/Imu”
        data source: 0x2311, 0x6405
<nav_msgs::Odometry>  “hgINS/Std/Odometry” [from LocalVertical to hgINS frame]
        data source: 0x6403, 0x6405, 0x6504
<sensor_msgs::NavSatFix> "hgINS/Std/NavSatFix“
        data source: 0x6403
<sensor_msgs::TimeReference> "hgINS/Std/TimeReference“
        data source: 0x6403
<geometry_msgs::TwistWithCovarianceStamped> "hgINS/Std/TwistWithCovarianceStamped“
        data source: 0x6405, 0x6504

and transformation function from ECEF to LocalVertical (point of initialization) and to hgINS position. Furthermore other transformations can be published to custom frames (/lidar /camera etc.). This transformation is handled by vehicle_tf.yaml configuration located in /launch/ folder.

/world -> /Local vertical -> /hgINS -> custom via vehicle_tf.yaml

Quick Start

Prerequisites:

1. Copy “hg_nav_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_nav_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

Report a Bug

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


2024-12-07 14:48