Show EOL distros: 

Package Summary

ROS driver for the BNO055 IMU using UART communication. It allows the configuration and calibration of the IMU

IMPORTANT: This wiki offers a starter guide. See the readme of the RoboticArts/ros_imu_bno055 repository for complete documentation

Overview

The ros_imu_bno055 package contains a ROS driver for the BNO055 IMU sensor. This package communicates with the IMU BNO055 using UART communication through a USB Serial Converter. It allows IMU calibration and configuration

this

The driver publishes the following data:

Requisites

  1. Ubuntu with ROS
  2. Python 3
  3. Bosch IMU BNO055
  4. USB Serial Converter

Hardware setup

There are different boards that incorporate the BNO055 IMU. The cheapest one is from Aliexpress. This board has two solder bridges called PS0 and PS1 used to select the type of communication.

To use the IMU in this package, it must be configured in UART mode to be able to communicate with the serial to USB converter. Therefore PS0 = 0 and PS1 = 1. Remember that on this board the solder bridges are inverted, so the PS1 bridge must be unsolder.

this this

Note: For different board, for example the Adafruit board or a different Chinese board, use this link

Finally, connect the IMU to the serial to USB converter. The Rx and Tx cables are crossed. The power of the BNO055 module is 5V

this

Installation

To install ros_imu_bno055 package:

$ cd ~/catkin_ws/src
$ git clone https://github.com/RoboticArts/ros_imu_bno055.git

It is important to compile the package so that the libraries are added correctly

$ cd ~/catkin_ws
$ catkin_make --only-pkg-with-deps ros_imu_bno055
$ source devel/setup.bash

Finally pyserial must be installed if it is not on the computer. This dependency is normally included in the standard ROS installation

$ pip install pyserial

Launch IMU

1. Make sure to connect the IMU well to the computer. Check the Hardware Setup section for more information

2. In a terminal, launch the following command to display the IMU in RVIZ

 $ roslaunch ros_imu_bno055 view_imu.launch

3. Move the IMU to view its orientation in RVIZ

this

IMU Calibration

BNO055 IMU has an internal factory calibration, however, it is highly recommended to calibrate it. The node imu_calibration takes care of it. To launch it:

$ roslaunch ros_imu_bno055 imu_calibration.launch operation_mode:=NDOF_FMC_OFF

This will generate a calibration file that will be used by the driver. Note that the calibration depends on the operating mode used, therefore it must be indicated.

this

Note: For more detailed instructions see readme

ROS API

ros_imu_bno055 / imu_ros

The imu_ros node publishes IMU data:

Published Topics

imu/data (sensor_msgs/Imu)
  • Includes linear accelerations and angular velocities and orientations.
imu/magnetometer (sensor_msgs/MagneticField)
  • The magnetic orientation vector
imu/temperature (sensor_msgs/Temperature)
  • Temperature ÂșC

Services

imu/reset_device (std_srvs/Empty)
  • Resets the orientation of the axis that is located perpendicular to the ground plane.
imu/calibration_status (std_srvs/Trigger)
  • Returns the current status of the calibration

Parameters

~serial_port (string, default: "/dev/ttyUSB0")
  • USB port where the IMU is connected (using a USB Serial Converter )
~frame_id (string, default: "imu_link")
  • Name of the link that the tf will use
~operation_mode (string, default: IMU)
  • Type of sensory fusion used by the IMU. See readme for more information
~oscillator (string, default: INTERNAL)
  • Set external oscillator to get more accurate clock vary for lower sensitivity error
~reset_orientation (bool, default: true)
  • Resets the IMU to resets the orientation of the axis that is located perpendicular to the ground plane.
~frequency (double, default: 50)
  • Frequency of reading the IMU and publication in ROS. The maximum frequency reached by the IMU is 50 Hz.
~use_magnetometer (bool, default: false)
  • Enables topic imu/magnetometer
~use_temperature (bool, default: false)
  • Enables topic imu/temperature

Wiki: ros_imu_bno055 (last edited 2020-08-06 21:40:46 by rvasquez)