witmotion.jpg

Overview

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.

Package URL: https://github.com/ElettraSciComp/witmotion_IMU_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)

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

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:

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

NOTE: All the topic names here are configurable. 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.

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).
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/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.

Report a Bug

Use GitHub to report bugs or submit feature requests. [View active issues]

Wiki: witmotion_ros (last edited 2022-05-13 13:15:19 by Andrey Vukolov)