Show EOL distros:
Package Summary
ROS driver for the BNO055 IMU using UART communication. It allows the configuration and calibration of the IMU
- Maintainer status: maintained
Maintainer: Robert Vasquez Zavaleta <roboticarts1 AT gmail DOT com>
Author: Robert Vasquez zavaleta <roboticarts1 AT gmail DOT com>
- License: BSD
Bug / feature tracker: https://github.com/RoboticArts/ros_imu_bno055/issues
Source: git https://github.com/RoboticArts/ros_imu_bno055.git
Contents
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
The driver publishes the following data:
linear acceleration, angular velocities and quaternion orientation as sensor_msgs/Imu
magnetic field as sensor_msgs/MagneticField
temperature as sensor_msgs/Temperature
Requisites
- Ubuntu with ROS
- Python 3
- Bosch IMU BNO055
- 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.
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
To install ros_imu_bno055 package: It is important to compile the package so that the libraries are added correctly Finally pyserial must be installed if it is not on the computer. This dependency is normally included in the standard ROS installation
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 3. Move the IMU to view its orientation in RVIZ
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: 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. Note: For more detailed instructions see readme
Installation
$ cd ~/catkin_ws/src
$ git clone https://github.com/RoboticArts/ros_imu_bno055.git
$ cd ~/catkin_ws
$ catkin_make --only-pkg-with-deps ros_imu_bno055
$ source devel/setup.bash
$ pip install pyserial
Launch IMU
$ roslaunch ros_imu_bno055 view_imu.launch
IMU Calibration
$ roslaunch ros_imu_bno055 imu_calibration.launch operation_mode:=NDOF_FMC_OFF
ROS API
ros_imu_bno055 / imu_ros
The imu_ros node publishes IMU data:
Published Topics
imu/data (sensor_msgs/Imu)
imu/magnetometer (sensor_msgs/MagneticField)
imu/temperature (sensor_msgs/Temperature) Services
imu/reset_device (std_srvs/Empty)
imu/calibration_status (std_srvs/Trigger) Parameters
~serial_port (string, default: "/dev/ttyUSB0")
~frame_id (string, default: "imu_link")
~operation_mode (string, default: IMU)
~oscillator (string, default: INTERNAL)
~reset_orientation (bool, default: true)
~frequency (double, default: 50)
~use_magnetometer (bool, default: false)
~use_temperature (bool, default: false)