Package Summary

Standalone QT-based IMU/GPS decoder nodes for Witmotion UART-compatible sensor devices

Package Summary

Standalone QT-based IMU/GPS decoder nodes for Witmotion UART-compatible sensor devices

Overview

witmotion.jpg

This package implements a ROS 1 wrapper for Witmotion IMU driver library. It reads the data from the family of TTL-compatible inertial pose estimation units (IMUs) manufactured by WitMotion Shenzhen Co.,Ltd publishing the information in a ROS-native way using sensor_msgs, geometry_msgs and std_msgs message definition packages. The port access model is implemented in a monopolistic way according to UNIX specifications, so only one instance of the module can be executed for the dedicated virtual device. The library allows programming of any control over the Witmotion sensors. There is native support for baud rates up to 115200 baud, and polling frequencies up to 200 Hz. Please refer to the example controller application to learn how to program a sensor that is not supported now.

The package was developed under Remotization and Robotization Initiative at Elettra Sincrotrone Trieste by the members of the ICT Group.

Installation

sudo apt install ros-${ROS_DISTRO}-witmotion-ros

Supported/tested Devices

The initial tests of the module were done using the following Witmotion sensor devices:

  • WT31N 3-Axis Accelerometer/Gyroscope(Linear accelerations + 2-axis Euler angles gravity tracking) - tested on baud rates 9600 and 115200 baud, polling frequencies up to 100 Hz.

  • JY901B 9-Axis Combined IMU/Magnetometer/Altimeter (Linear accelerations, angular velocities, Euler angles, magnetic field, barometry, altitude)

  • WT901 9-Axis Combined Open Circuit IMU/Magnetometer (Linear accelerations, angular velocities, Euler angles, magnetic field) - tested on baud rates from 2400 to 115200 baud, polling frequencies up to 150 Hz.

The polling frequency of 200 Hz declared by Witmotion is actually a packet drop frequency which is slightly higher than the maximal possible measurement frequency.

Community-driven tests

  • HWT905 TTL 9-Axis IP67 Enclosed Combined IMU/Magnetometer/Altimeter/Inclinometer (Linear accelerations, angular velocities, Euler angles, magnetic field, barometry, altitude, calibrated native quaternion), equipped with original USB transceiver - tested by Vincent Foucault on 115200 baud, measurement frequencies from 10 up to 200 Hz and polling frequencies up to 100 Hz.

  • WTGAHRS1 TTL 10-Axis IP-54-Enclosed Combined IMU/Magnetometer/Altimeter/Barometer/Inclinometer/GPS receiver - tested (also as a GPS receiver) by Qing Joe Wong on baudrates from 4800 to 230400 baud, polling frequencies up to 200 Hz.

Actual bandwidth and measurement frequencies

According to the official Witmotion command table, the available bandwidth values and connected measurement frequencies are the following:

Measurement frequency

256 (if supported)

184

94

44

21

10

5

Hz

ID value

0x00

0x01

0x02

0x03

0x04

0x05

0x06

HEX

Datasheets and official documentation

The module is developed according to the specifications released by Witmotion, the presented snapshot has a download date is 23.02.2022. The official website https://wiki.wit-motion.com is not always accessible, so the PDF snapshots are placed under IPFS web directory:

As additional material, there is the command table, consisting of the list of special commands used to configure 9XX series of sensors.

Published message types

The module published the following message types (once the incoming data is available from the sensor, all the topic names and publisher availability are configurable):

Nodes

All the topic names listed here are configurable. The general rule is the following: the topic name is taken from the configuration parameter naming the corresponding publisher: <measurement-name>_publisher/topic_name. One can adjust the topic names using a config file. Also, all publishers of the node except IMU, orientation and GPS publishers, are ready for linear calibration because there can be differences in decoding coefficients between the sensors (proven for WT31N and JY901B sensors). To set the linear calibration for a publisher, use coefficient and addition parameters in the dedicated configuration namespace (see the sample config file).

witmotion_imu

Opens a serial port to read data from Witmotion sensor.

Published Topics

imu (sensor_msgs/Imu)
  • IMU measurement output.
temperature (sensor_msgs/Temperature)
  • Temperature observation.
magnetometer (sensor_msgs/MagneticField)
  • Magnetometer output.
barometer (sensor_msgs/FluidPressure)
  • Athmospheric pressure.
altitude (std_msgs/Float64)
  • Geographic altitude.
orientation (geometry_msgs/Quaternion)
  • Raw orientation.
gps (sensor_msgs/NavSatFix)
  • GPS fix position.
gps_altitude (std_msgs/Float32)
  • GPS altimeter.
gps_satellites (std_msgs/UInt32)
  • Number of the GPS active satellite IDs.
gps_variance (geometry_msgs/Vector3)
  • GPS position variance vector (ENU orientation).
gps_ground_speed (geometry_msgs/Twist)
  • GPS ground speed.
witmotion_clock (rosgraph_msgs/Clock)
  • Realtime clock information provided by the sensor (if available).

Services

restart_imu (std_srvs/Empty)
  • Call this service to restart the UART kernel bridge after sensor error is occurred.

Parameters

restart_service_name (string, default: /restart_imu)
  • Service name to advertise the after-error-restart function.
port (string, default: ttyUSB0)
  • The virtual kernel device name for a serial port.
baud_rate (integer, default: 9600)
  • Port rate value to be used by the library for opening the port.
polling_interval (integer, default: 50)
  • The sensor polling interval in milliseconds. If this parameter is omitted, the default value is set up by the library (50 ms).
timeout_ms (integer, default: 50)
  • Sensor timeout period in milliseconds. If no data is received from the sensor after this period, then an error is raised and the node terminates. If this parameter is omitted, a default value of 3 times the polling interval is used. If this parameter is zero, the timeout check is disabled.
imu_publisher/topic_name (string, default: /imu)
  • Topic name for IMU data publisher.
imu_publisher/frame_id (string, default: imu)
  • IMU message header frame.
imu_publisher/use_native_orientation (bool, default: false)
  • Instructs the node to use the native quaternion orientation measurement from the sensor instead of the one synthesized from Euler angles.
imu_publisher/measurements (group)
  • Includes presence control for IMU components: acceleration, angular_velocity, orientation. Every component includes enabled flag and row-major 3x3 matrix defining covariance (see the sample config file)
temperature_publisher/topic_name (string, default: /temperature)
  • Temperature topic name.
temperature_publisher/frame_id (string, default: base_link)
  • Temperature message header frame.
temperature_publisher/enabled (bool, default: true)
  • Enables/disables temperature measurement extraction.
temperature_publisher/from_message (string, default: acceleration)
  • Message type string to determine from which type of Witmotion measurement message the temperature data should be extracted (please refer to the original documentation for a detailed description). The possible values are: acceleration, angular_vel, orientation or magnetometer.
temperature_publisher/variance (float, default: 0)
  • Constant variance, if applicable, otherwise 0.
magnetometer_publisher/topic_name (string, default: /magnetometer)
  • Magnetometer topic name.
magnetometer_publisher/frame_id (string, default: base_link)
  • Magnetometer message header frame.
magnetometer_publisher/enabled (bool, default: true)
  • Enables/disables magnetic measurement extraction.
magnetometer_publisher/covariance (Row-major matrix 3x3)
  • Static covariance, all zeros for unknown
barometer_publisher/enabled (bool, default: true)
  • Enables/disables barometer measurement extraction.
barometer_publisher/variance (float, default: 0)
  • Constant variance, if applicable, otherwise 0.
barometer_publisher/frame_id (string, default: base_link)
  • Pressure message header frame.
barometer_publisher/topic_name (string, default: /barometer)
  • Barometer topic name.
altimeter_publisher/enabled (bool, default: true)
  • Enables/disables altimeter measurement extraction.
altimeter_publisher/topic_name (string, default: /altimeter)
  • Altimeter topic name.
orientation_publisher/topic_name (string, default: /orientation)
  • Orientation topic name.
orientation_publisher/enabled (bool, default: false)
  • Enables/disables orientation measurement extraction.
gps_publisher/enabled (bool, default: false)
  • Enables/disables all GPS receiver measurements extraction.
gps_publisher/navsat_fix_frame_id (string, default: world)
  • Frame ID for GPS fixed position publisher.
gps_publisher/navsat_fix_topic_name (string, default: /gps)
  • Topic name for GPS fixed position publisher.
gps_publisher/navsat_altitude_topic_name (string, default: /gps_altitude)
  • Topic name for GPS altitude publisher.
gps_publisher/navsat_satellites_topic_name (string, default: /gps_satellites)
  • Topic name for GPS active satellites number publisher.
gps_publisher/navsat_variance_topic_name (string, default: /gps_variance)
  • Topic name for GPS diagonal variance publisher.
gps_publisher/ground_speed_topic_name (string, default: /gps_ground_speed)
  • Topic name for GPS ground speed publisher.
rtc_publisher/enabled (bool, default: false)
  • Enables/disables realtime clock decoder/publisher.
rtc_publisher/topic_name (string, default: /witmotion_clock)
  • Topic name for realtime clock information publisher.
rtc_publisher/presync (bool, default: true)
  • Instructs the node to perform an attempt to pre-synchronize the sensor's internal realtime clock.

Report a Bug

Usage of controller applications

The underlying library is shipped with a set of controller applications. They allow the users to set up sensors' internal parameters and specify output data. These applications could be run using rosrun. Here only the brief list and set of usage examples is presented. Please refer to the underlying library documentation for a detailed description of controller applications and their options.

Message Enumerator

This application enumerates and catalogizes all messages emitted by the sensor once they comply with Witmotion 11-byte serial protocol. Use this message_enumerator to determine the desired baudrate, port and exact message set your sensor produces. The following example demonstrates the running of enumeration from /dev/ttyUSB0 port on 115200 baud with a polling interval of 10 ms.

rosrun witmotion_ros message-enumerator -d ttyUSB0 -b 115200 -p 10

Troubleshooting

Please refer to the dedicated Troubleshooting wiki page.

Citation

ROS module

DOI: 10.5281/zenodo.7682518

Modern BibTeX

@software{witmotion_ros_2023,
  author       = {Vukolov, Andrey and Kitagawa, Shingo and ElettraSciComp and
                  Baskara and
                  zacharykratochvil},
  title        = {{ElettraSciComp/witmotion\_IMU\_ros: Version 1.2.27}},
  month        = August,
  year         = 2023,
  publisher    = {Zenodo},
  version      = {1.2.27},
  doi          = {10.5281/zenodo.7682518},
  url          = {https://doi.org/10.5281/zenodo.7682518}
}

Plain BibTeX

@misc{witmotion_ros_2023,
  author       = {Vukolov, Andrey and Kitagawa, Shingo and ElettraSciComp and
                  Baskara and
                  zacharykratochvil},
  title        = {{ElettraSciComp/witmotion\_IMU\_ros: Version 1.2.27}},
  year         = 2023,
  publisher    = {Zenodo},
  doi          = {10.5281/zenodo.7682518},
  howpublished = {Github Releases \url{https://github.com/ElettraSciComp/witmotion_IMU_ros/tree/1.2.27}}
}

Library

DOI: 10.5281/zenodo.7017118

Modern BibTeX

@software{andrei_vukolov_2022_7017118,
  author       = {Vukolov, Andrey},
  title        = {ElettraSciComp/witmotion\_IMU\_QT: Version 0.9.17},
  month        = August,
  year         = 2022,
  publisher    = {Zenodo},
  version      = {v0.9.17-alpha},
  doi          = {10.5281/zenodo.7017118},
  url          = {https://doi.org/10.5281/zenodo.7017118}
}

Plain BibTeX

@misc{andrei_vukolov_2022_7017118,
  author       = {Vukolov, Andrey},
  title        = {ElettraSciComp/witmotion\_IMU\_QT: Version 0.9.17},
  year         = 2022,
  publisher    = {Zenodo},
  doi          = {10.5281/zenodo.7017118},
  howpublished = {Github Releases \url{https://github.com/ElettraSciComp/witmotion_IMU_QT/releases/tag/v0.9.17-alpha}}
}

Wiki: witmotion_ros (last edited 2024-03-07 14:01:59 by Andrey Vukolov)