Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add I2C implementation #52

Merged
merged 7 commits into from
Jan 14, 2023

Conversation

asymingt
Copy link
Contributor

@asymingt asymingt commented Dec 6, 2022

This modifies the code to add I2C support for the BNO055 sensor using the smbus library for I2C access. It adds i2c_bus and i2c_addr parameters to define the bus and address for the chip.

TODO list:

  • Check that UART is not broken as a result of this change
  • Work out why magnetic field readings are all zeros
  • Work out why we get a ZeroDevisionError on startup

Tested on a Google Coral Dev Mini board.

[bno055-4] [INFO] [1670349295.067779214] [bno055_imu_node]: Initializing parameters
[bno055-4] [INFO] [1670349295.226606079] [bno055_imu_node]: Parameters set to:
[bno055-4] [INFO] [1670349295.237909569] [bno055_imu_node]: 	ros_topic_prefix:	"bno055/"
[bno055-4] [INFO] [1670349295.246089261] [bno055_imu_node]: 	connection_type:	"i2c"
[bno055-4] [INFO] [1670349295.254703418] [bno055_imu_node]: 	i2c_bus:		"0"
[bno055-4] [INFO] [1670349295.269453248] [bno055_imu_node]: 	i2c_addr:		"40"
[bno055-4] [INFO] [1670349295.288136576] [bno055_imu_node]: 	uart_port:		"/dev/ttyUSB0"
[bno055-4] [INFO] [1670349295.305530661] [bno055_imu_node]: 	uart_baudrate:		"115200"
[bno055-4] [INFO] [1670349295.312030337] [bno055_imu_node]: 	uart_timeout:		"0.1"
[bno055-4] [INFO] [1670349295.339739595] [bno055_imu_node]: 	frame_id:		"bno055"
[bno055-4] [INFO] [1670349295.346247194] [bno055_imu_node]: 	data_query_frequency:	"100"
[bno055-4] [INFO] [1670349295.381144366] [bno055_imu_node]: 	calib_status_frequency:	"0.1"
[bno055-4] [INFO] [1670349295.417296241] [bno055_imu_node]: 	operation_mode:		"12"
[bno055-4] [INFO] [1670349295.431217601] [bno055_imu_node]: 	placement_axis_remap:	"P2"
[bno055-4] [INFO] [1670349295.440816383] [bno055_imu_node]: 	acc_factor:		"100.0"
[bno055-4] [INFO] [1670349295.448194452] [bno055_imu_node]: 	mag_factor:		"16000000.0"
[bno055-4] [INFO] [1670349295.461348882] [bno055_imu_node]: 	gyr_factor:		"900.0"
[bno055-4] [INFO] [1670349295.469705729] [bno055_imu_node]: 	set_offsets:		"False"
[bno055-4] [INFO] [1670349295.477400878] [bno055_imu_node]: 	offset_acc:		"[65516, 165, 65512]"
[bno055-4] [INFO] [1670349295.487703359] [bno055_imu_node]: 	radius_acc:		"1000"
[bno055-4] [INFO] [1670349295.497006907] [bno055_imu_node]: 	offset_mag:		"[65460, 65182, 637]"
[bno055-4] [INFO] [1670349295.504581670] [bno055_imu_node]: 	radius_mag:		"0"
[bno055-4] [INFO] [1670349295.511741121] [bno055_imu_node]: 	offset_gyr:		"[2, 65535, 65535]"
[bno055-4] [INFO] [1670349295.520134199] [bno055_imu_node]: 	variance_acc:		"[0.017, 0.017, 0.017]"
[bno055-4] [INFO] [1670349295.527464729] [bno055_imu_node]: 	variance_angular_vel:	"[0.04, 0.04, 0.04]"
[bno055-4] [INFO] [1670349295.541111010] [bno055_imu_node]: 	variance_orientation:	"[0.0159, 0.0159, 0.0159]"
[bno055-4] [INFO] [1670349295.548788005] [bno055_imu_node]: 	variance_mag:		"[0.0, 0.0, 0.0]"
[bno055-4] [INFO] [1670349295.653781137] [bno055_imu_node]: Configuring device...
[bno055-4] [INFO] [1670349295.665464323] [bno055_imu_node]: Current sensor offsets:
[bno055-4] [INFO] [1670349295.679366299] [bno055_imu_node]: 	Accel offsets (x y z): 0 1 3
[bno055-4] [INFO] [1670349295.685914744] [bno055_imu_node]: 	Accel radius: 1000
[bno055-4] [INFO] [1670349295.692526114] [bno055_imu_node]: 	Mag offsets (x y z): 0 0 0
[bno055-4] [INFO] [1670349295.698720325] [bno055_imu_node]: 	Mag radius: 0
[bno055-4] [INFO] [1670349295.705520927] [bno055_imu_node]: 	Gyro offsets (x y z): 0 0 0
[bno055-4] [INFO] [1670349295.712171989] [bno055_imu_node]: Setting device_mode to 12
[bno055-4] [INFO] [1670349295.719500904] [bno055_imu_node]: Bosch BNO055 IMU configuration complete.

I do get two warnings about the first few readings being zero after initial configuration.

[bno055-4] [WARN] [1670349295.757589413] [bno055_imu_node]: Receiving sensor data failed with ZeroDivisionError:"float division by zero"
[rosbridge_websocket-1] [INFO] [1670349295.769806834] [rosbridge_server_node]: Rosbridge WebSocket server started on port 54321
[bno055-4] [WARN] [1670349295.786740146] [bno055_imu_node]: Receiving sensor data failed with ZeroDivisionError:"float division by zero"

IMU data looks to not be garbage:

Screenshot from 2022-12-06 10-02-15

Copy link

@github-actions github-actions bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thankyou for creating your first PR! Contributions like yours is what it is all about. Keep it up!

@flynneva
Copy link
Owner

flynneva commented Dec 7, 2022

@asymingt hey hey this is awesome stuff! I try to carve some time out soon to review this and test the UART stuff.

So cool btw to hear this is working on a google coral board - haven't gotten one myself but they definitely look cool!

@asymingt
Copy link
Contributor Author

asymingt commented Dec 7, 2022

@asymingt hey hey this is awesome stuff! I try to carve some time out soon to review this and test the UART stuff.

So cool btw to hear this is working on a google coral board - haven't gotten one myself but they definitely look cool!

@flynneva, glad you appreciate the contribution. The code does work, but it's not particularly high-performance. I'm seeing ~60Hz throughput when the node is run without anything else:

root@red-umpire:~# ros2 topic hz /bno055/mag
average rate: 61.433
	min: 0.014s max: 0.017s std dev: 0.00088s window: 63
average rate: 61.174
	min: 0.014s max: 0.018s std dev: 0.00086s window: 124
average rate: 61.432
	min: 0.014s max: 0.018s std dev: 0.00090s window: 186
average rate: 61.537
	min: 0.014s max: 0.018s std dev: 0.00092s window: 248
average rate: 61.606
	min: 0.014s max: 0.018s std dev: 0.00092s window: 310

Also, the magnetic field sensor is somehow now also working, although I think the scale factor is off.

@asymingt
Copy link
Contributor Author

asymingt commented Dec 7, 2022

@asymingt hey hey this is awesome stuff! I try to carve some time out soon to review this and test the UART stuff.
So cool btw to hear this is working on a google coral board - haven't gotten one myself but they definitely look cool!

@flynneva, glad you appreciate the contribution. The code does work, but it's not particularly high-performance. I'm seeing ~60Hz throughput when the node is run without anything else:

root@red-umpire:~# ros2 topic hz /bno055/mag
average rate: 61.433
	min: 0.014s max: 0.017s std dev: 0.00088s window: 63
average rate: 61.174
	min: 0.014s max: 0.018s std dev: 0.00086s window: 124
average rate: 61.432
	min: 0.014s max: 0.018s std dev: 0.00090s window: 186
average rate: 61.537
	min: 0.014s max: 0.018s std dev: 0.00092s window: 248
average rate: 61.606
	min: 0.014s max: 0.018s std dev: 0.00092s window: 310

Also, the magnetic field sensor is somehow now also working, although I think the scale factor is off.

These results are actually comparable to a pure C++ implementation (https://github.com/bdholt1/ros2_bno055_sensor) so I suspect this might have to do with (1) bus speed limitations, or (2) IPC overhead. I'm leaning towards the former.

@asymingt
Copy link
Contributor Author

asymingt commented Dec 11, 2022

Worked out that we are bus limited -- it's either the i2c bus or the chip that is holding back the sampling frequency. Knowing this, I can get ~100Hz raw IMU and ~20Hz magnetometer with this PR, where I've separated our the publication into smaller i2c transactions.

https://github.com/asymingt/bno055/pull/1/files#diff-37a67ff78eb7260214b323353263b9af40a2fa98719a1e81937fae0159df87a3

But I have to disable quaternion and gravitational vector publication:

# For streaming raw inertial data.
Node(
    package='bno055',
    executable='bno055',
    name='bno055_imu_node',
    parameters=[
        { "ros_topic_prefix": "bno055/" },
        { "connection_type": "i2c" },
        { "i2c_bus": 0 },
        { "i2c_addr": 0x28 },
        { "imu_query_frequency": 100 },
        { "rot_query_frequency": 0 },
        { "gra_query_frequency": 0 },
        { "mag_query_frequency": 20 },
        { "tmp_query_frequency": 1 },
        { "cal_query_frequency": 1 },
        { "frame_id": "bno055" },
        { "operation_mode": 0x0C },
        { "placement_axis_remap": "P2" },
        { "acc_factor": 100.0 },
        { "mag_factor": 16000000.0 },
        { "gyr_factor": 900.0 },
        { "set_offsets" : False },
        { "offset_acc": [0xFFEC, 0x00A5, 0xFFE8] },
        { "offset_mag": [0xFFB4, 0xFE9E, 0x027D] },
        { "offset_gyr": [0x0002, 0xFFFF, 0xFFFF] }
    ],
    output='screen'
),

Here are my results on a Coral Dev Mini Board:

root@red-umpire:~/cover# ros2 topic hz /bno055/imu
average rate: 97.078
	min: 0.003s max: 0.030s std dev: 0.00531s window: 98
average rate: 97.799
	min: 0.003s max: 0.030s std dev: 0.00493s window: 197
average rate: 98.192
	min: 0.003s max: 0.030s std dev: 0.00510s window: 296
average rate: 97.628
	min: 0.003s max: 0.031s std dev: 0.00499s window: 392
average rate: 98.233
	min: 0.003s max: 0.031s std dev: 0.00501s window: 493
average rate: 98.458
	min: 0.003s max: 0.031s std dev: 0.00504s window: 593
average rate: 98.334
	min: 0.003s max: 0.031s std dev: 0.00492s window: 691
average rate: 98.150
	min: 0.003s max: 0.031s std dev: 0.00494s window: 789
average rate: 98.478
	min: 0.003s max: 0.031s std dev: 0.00489s window: 891
average rate: 98.527
	min: 0.003s max: 0.031s std dev: 0.00487s window: 990
average rate: 98.546
	min: 0.003s max: 0.031s std dev: 0.00493s window: 1089
...
root@red-umpire:~/cover# ros2 topic hz /bno055/mag
average rate: 20.013
	min: 0.042s max: 0.055s std dev: 0.00297s window: 22
average rate: 19.993
	min: 0.034s max: 0.065s std dev: 0.00413s window: 42
average rate: 19.993
	min: 0.034s max: 0.065s std dev: 0.00351s window: 62
average rate: 20.004
	min: 0.034s max: 0.065s std dev: 0.00332s window: 83
average rate: 20.002
	min: 0.034s max: 0.065s std dev: 0.00324s window: 103
average rate: 19.998
	min: 0.034s max: 0.065s std dev: 0.00309s window: 123
average rate: 19.993
	min: 0.034s max: 0.065s std dev: 0.00297s window: 143
average rate: 19.997
	min: 0.034s max: 0.065s std dev: 0.00304s window: 164
average rate: 19.996
	min: 0.034s max: 0.065s std dev: 0.00305s window: 184
average rate: 19.998
	min: 0.034s max: 0.065s std dev: 0.00316s window: 205

Copy link
Owner

@flynneva flynneva left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@asymingt overall awesome PR!!!! Love the work you did here and other than a few small comments everything looks great!

bno055/params/bno055_params.yaml Outdated Show resolved Hide resolved
bno055/params/NodeParameters.py Outdated Show resolved Hide resolved
bno055/params/NodeParameters.py Outdated Show resolved Hide resolved
bno055/connectors/i2c.py Outdated Show resolved Hide resolved
@flynneva
Copy link
Owner

flynneva commented Dec 12, 2022

Worked out that we are bus limited -- it's either the i2c bus or the chip that is holding back the sampling frequency. Knowing this, I can get ~100Hz raw IMU and ~20Hz magnetometer with this PR, where I've separated our the publication into smaller i2c transactions.

@asymingt this might be something we can just add to the docs later so others know this as well for I2C. If you want to add it to this PR feel free, but also we can just add it in another PR later as well...not a big deal either way.

@asymingt
Copy link
Contributor Author

@flynneva I think I addressed your review comments. I added a couple of copyright headers to files that didn't have them. Hopefully that's OK.

@asymingt
Copy link
Contributor Author

asymingt commented Jan 3, 2023

@flynneva feel free to merge this when you're ready to add the changes.

@flynneva
Copy link
Owner

flynneva commented Jan 5, 2023

@asymingt yes sorry! I am traveling for work this week (at CES) so I won't get to it this week but will make it a priority next week.

@flynneva flynneva merged commit b96c8d1 into flynneva:main Jan 14, 2023
@flynneva
Copy link
Owner

@asymingt again, thank you for the contribution! 🙏🏼 stuff like this is what makes the ROS / OSS community so great 👏🏼


try:
self.serialConnection.write(buf_out)
buf_in = bytearray(self.serialConnection.read())
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This line should be buf_in = bytearray(self.serialConnection.read(2)) since the UART protocol register write answers with two bytes (preferably 0xEE 0X01 - Write success) which is tested later in line 140. Additional reasoning: previous implementation in bno055/connectors/Connector.py line 126 and datasheet page 93.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

#57

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants