Code Monkey home page Code Monkey logo

ros-imu-bno055's Introduction

ROS1/ROS2 C++ driver for Bosch BNO055 IMU (I2C)

This is a light weight, C++ ROS node for the BNO055 IMU that communicates via I2C and without any dependencies besides libi2c-dev. It is specifically targeted at using a BNO055 with NVIDIA Jetson (Xavier, Orin, etc.) platforms but should work with a Raspberry Pi 5, or in an earlier Raspberry Pi using the software I2C mode.

The BNO055 supports I2C and UART communication. This driver supports I2C only. If you are looking for a UART driver, see this driver by mdrwiega instead.

Where to buy

Installation

Install the prerequisites:

sudo apt install libi2c-dev

Copy or rename the appropriate CMakeLists file:

cp CMakeLists.ros1.txt CMakeLists.txt    # for ROS1
cp CMakeLists.ros2.txt CMakeLists.txt    # for ROS2

and then you are ready to drop this package into a catkin (ROS1) or colcon (ROS2) workspace.

How to run

rosrun imu_bno055 bno055_i2c_node        # for ROS1
ros2 run imu_bno055 bno055_i2c_node      # for ROS2

Parameters:

  • device -- the path to the i2c device. Default is /dev/i2c-1. Use i2cdetect in the i2c-tools package to find out which bus your IMU is on.
  • address -- the i2c address of the IMU. Default is 0x28.

Outputs topics:

  • /data (sensor_msgs/Imu) -- fused IMU data
  • /raw (sensor_msgs/Imu) -- raw accelerometer data
  • /mag (sensor_msgs/MagneticField) -- raw magnetic field data
  • /temp (sensor_msgs/Temperature) -- temperature data
  • /status (diagnostic_msgs/DiagnosticStatus) -- a DiagnosticStatus object showing the current calibration, interrupt, system status of the IMU

Service calls:

  • /reset (std_srvs/Trigger) -- resets the IMU
  • /calibrate (std_srvs/Trigger) -- not yet implemented

Usage notes

Raspberry Pi

The Raspberry Pi <=4 hardware I2C does not support clock stretching. You have a few options:

NVIDIA Jetson platforms

You may need to add your user to the i2c group, e.g. sudo usermod -aG i2c nvidia. It should just work after that.

ros-imu-bno055's People

Contributors

dheera avatar gcullie avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar

ros-imu-bno055's Issues

Execute

Hello dheera.
Amazing your work will be much easier because you don't have to use RTIMUlib but I don't know how to run it, would it be with an ide or Qt creator? (I use jetson TX2)
Thank you very much in advance.

No absolute orientation

Hi,
I can't seem to get the absolute orientation of the bno055 working. Every time I launch the node, the orientation in /imu/data always starts at around [0, 0, 0, 1], regardless of the orientation of the imu. In /imu/raw, the orientation is always [0, 0, 0, 0] and never changes.

Wiring

Hi, how did you wire bno055 to tx2?

vin -> 5v
gnd -> gnd
sda -> sda(A4)
scl -> scl(A5)

Do I just wire like above between tx2 and bno055 directly?

High rate raw data

Hi @dheera

I would like to get high rate (~200Hz) of the raw data (accelerometer and gyroscope) to use with some visual inertial navigation frameworks.

Is this achievable using this driver? IF yes, what needs to be done? Is it related to

nh_priv->param("rate", param_rate, (double)100);

Thanks

Calibration

Hi @dheera
Thanks for this package.

Is there a way to calibrate the IMU? I believe this is important to give reasonable values for custom platform setup.
Thanks.

Calibration status values

Hello,
The calibration status data is supposed to be between 0 and 3, but it doesn't seem to be the case for this driver as can be seen below:

Screenshot from 2022-10-19 14-37-07

Can you explain the meaning of these values?

Thank you very much

The IMU upside down suddenly

When I launch the imu file connecting to my urdf to build a map using cartographer, first it is good, but after several seconds the urdf is suddenly upside down, and it makes the rotation fault, if I move the imu to the left, my robot model (urdf) that had been upside down will turn to the right.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    ๐Ÿ–– Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. ๐Ÿ“Š๐Ÿ“ˆ๐ŸŽ‰

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google โค๏ธ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.