IMU
Module for interfacing with IMU sensors using the MSCL and Adafruit libraries.
This module provides two IMU sensor implementations
- LordMicrostrainIMU: Uses the MSCL library to interface with a Lord Microstrain IMU.
- BNO055: Uses the Adafruit BNO055 library to interface with a Bosch BNO055 IMU.
Dependencies
- MSCL (for LordMicrostrainIMU): https://github.com/LORD-MicroStrain/MSCL/tree/master
- adafruit_bno055, board, busio (for BNO055)
Ensure that the required libraries are installed and that the library paths are added to PYTHONPATH or sys.path if necessary.
BNO055
¶
Bases: IMUBase
Sensor class for the Bosch BNO055 IMU.
This class wraps the Adafruit BNO055 library to provide an interface consistent with the OSL sensor framework.
Connections
- The sensor should be connected to the main I2C bus.
- UART connectivity is not implemented.
Requirements
- adafruit_bno055
- board
- busio
Date
8/22/2024
Source code in opensourceleg/sensors/imu.py
452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 |
|
acc_x: float
property
¶
Get the measured acceleration along the x-axis in m/s².
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
Acceleration (m/s²) along the x-axis. |
acc_y: float
property
¶
Get the measured acceleration along the y-axis in m/s².
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
Acceleration (m/s²) along the y-axis. |
acc_z: float
property
¶
Get the measured acceleration along the z-axis in m/s².
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
Acceleration (m/s²) along the z-axis. |
gyro_x: float
property
¶
Get the measured rotational velocity about the x-axis in rad/s.
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
Angular velocity (rad/s) about the x-axis. |
gyro_y: float
property
¶
Get the measured rotational velocity about the y-axis in rad/s.
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
Angular velocity (rad/s) about the y-axis. |
gyro_z: float
property
¶
Get the measured rotational velocity about the z-axis in rad/s.
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
Angular velocity (rad/s) about the z-axis. |
is_streaming: bool
property
¶
Check if the BNO055 sensor is streaming data.
Returns:
Name | Type | Description |
---|---|---|
bool |
bool
|
True if streaming; otherwise, False. |
__init__(tag='BNO055', addr=40, offline=False)
¶
Initialize the BNO055 sensor.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
addr |
int
|
I2C address of the BNO055 sensor. Defaults to 40. |
40
|
Source code in opensourceleg/sensors/imu.py
configure_IMU_settings()
¶
Configure the BNO055 sensor settings.
Hard-coded configuration
- Enables external crystal.
- Sets mode to ACCGYRO_MODE.
- Configures accelerometer range to ACCEL_2G and bandwidth to ACCEL_15_63HZ.
- Configures gyroscope range to GYRO_1000_DPS and bandwidth to GYRO_23HZ.
Source code in opensourceleg/sensors/imu.py
start()
¶
Start the BNO055 sensor.
Initializes the I2C bus, creates an instance of the Adafruit BNO055 sensor, configures the sensor settings, and sets the streaming flag to True.
Source code in opensourceleg/sensors/imu.py
stop()
¶
update()
¶
Update the sensor data from the BNO055.
Reads the latest acceleration and gyroscopic data from the sensor.
Source code in opensourceleg/sensors/imu.py
LordMicrostrainIMU
¶
Bases: IMUBase
Sensor class for the Lord Microstrain IMU.
This class interfaces with a Lord Microstrain Inertial Measurement Unit (IMU) via the MSCL library. It returns Euler angles (in radians), angular rates (in rad/s), and linear accelerations (in m/s^2).
Resources
- Download v0.65 MSCL pre-built package for Raspbian: https://github.com/LORD-MicroStrain/MSCL/releases/download/v65.0.0/python3-mscl_65.0.0_arm64.deb
- Read the MSCL installation instructions: https://github.com/LORD-MicroStrain/MSCL/blob/master/HowToUseMSCL.md
- We assume that the MSCL library is installed in /usr/share/python3-mscl
Source code in opensourceleg/sensors/imu.py
23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 |
|
acc_x: float
property
¶
Get the estimated linear acceleration along the x-axis in m/s².
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
Linear acceleration (m/s²) along the x-axis. |
acc_y: float
property
¶
Get the estimated linear acceleration along the y-axis in m/s².
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
Linear acceleration (m/s²) along the y-axis. |
acc_z: float
property
¶
Get the estimated linear acceleration along the z-axis in m/s².
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
Linear acceleration (m/s²) along the z-axis. |
baud_rate: int
property
¶
Get the baud rate used for the sensor connection.
Returns:
Name | Type | Description |
---|---|---|
int |
int
|
The baud rate. |
data: dict[str, float]
property
¶
Get the latest sensor data.
Returns:
Type | Description |
---|---|
dict[str, float]
|
dict[str, float]: A dictionary mapping channel names to their float values. |
frequency: int
property
¶
Get the data streaming frequency of the sensor.
Returns:
Name | Type | Description |
---|---|---|
int |
int
|
The streaming frequency in Hz. |
gyro_x: float
property
¶
Get the measured gyroscopic value for the x-axis.
Note
Gyro data is not available for the Lord Microstrain IMU, so this returns 0.0 and logs a warning.
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
0.0 |
gyro_y: float
property
¶
Get the measured gyroscopic value for the y-axis.
Note
Gyro data is not available for the Lord Microstrain IMU, so this returns 0.0 and logs a warning.
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
0.0 |
gyro_z: float
property
¶
Get the measured gyroscopic value for the z-axis.
Note
Gyro data is not available for the Lord Microstrain IMU, so this returns 0.0 and logs a warning.
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
0.0 |
is_streaming: bool
property
¶
Check if the sensor is currently streaming data.
Returns:
Name | Type | Description |
---|---|---|
bool |
bool
|
True if streaming; otherwise, False. |
max_packets: int
property
¶
Get the maximum number of packets to retrieve.
pitch: float
property
¶
Get the estimated pitch angle in radians.
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
Pitch angle (rad). |
port: str
property
¶
Get the serial port used by the sensor.
Returns:
Name | Type | Description |
---|---|---|
str |
str
|
The serial port. |
return_packets: bool
property
¶
Get the return packets flag.
roll: float
property
¶
Get the estimated roll angle in radians.
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
Roll angle (rad). |
timestamp: float
property
¶
Get the timestamp of the latest data packet in seconds.
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
Timestamp (s) from the sensor data. |
update_timeout: int
property
¶
Get the update timeout for the sensor.
vel_x: float
property
¶
Get the estimated angular velocity about the x-axis in rad/s.
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
Angular velocity (rad/s) about the x-axis. |
vel_y: float
property
¶
Get the estimated angular velocity about the y-axis in rad/s.
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
Angular velocity (rad/s) about the y-axis. |
vel_z: float
property
¶
Get the estimated angular velocity about the z-axis in rad/s.
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
Angular velocity (rad/s) about the z-axis. |
yaw: float
property
¶
Get the estimated yaw angle in radians.
Returns:
Name | Type | Description |
---|---|---|
float |
float
|
Yaw angle (rad). |
__init__(tag='LordMicrostrainIMU', port='/dev/ttyUSB0', baud_rate=921600, frequency=200, update_timeout=500, max_packets=1, return_packets=False, offline=False)
¶
Initialize the LordMicrostrainIMU sensor.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
port |
str
|
Serial port for the IMU. Defaults to "/dev/ttyUSB0". |
'/dev/ttyUSB0'
|
baud_rate |
int
|
Baud rate for the serial connection. Defaults to 921600. |
921600
|
frequency |
int
|
Data streaming frequency in Hz. Defaults to 200. |
200
|
update_timeout |
int
|
Timeout for data packet retrieval in milliseconds. Defaults to 500. |
500
|
max_packets |
int
|
Maximum number of data packets to retrieve. Defaults to 1. |
1
|
return_packets |
bool
|
If True, returns the raw data packets. Defaults to False. |
False
|
Source code in opensourceleg/sensors/imu.py
ping()
¶
Ping the Lord Microstrain IMU sensor to verify connectivity.
Logs an info message if the ping is successful, otherwise logs an error.
Raises:
Type | Description |
---|---|
SensorNotStreamingException
|
If the sensor is not currently streaming. |
Source code in opensourceleg/sensors/imu.py
set_max_packets(max_packets)
¶
set_return_packets(return_packets)
¶
set_update_timeout(timeout)
¶
start()
¶
Start the Lord Microstrain IMU sensor.
Establishes a serial connection, configures the MIP channels, enables data streaming, and sets the streaming flag to True.
Source code in opensourceleg/sensors/imu.py
stop()
¶
Stop the Lord Microstrain IMU sensor.
Sets the node to idle mode and updates the streaming flag to False.
Raises:
Type | Description |
---|---|
SensorNotStreamingException
|
If the sensor is not currently streaming. |
Source code in opensourceleg/sensors/imu.py
update()
¶
Retrieve and update IMU data from the sensor. To modify update parameters, use the set_update_timeout, set_max_packets, and set_return_packets methods.
Returns:
Type | Description |
---|---|
Union[None, Any]
|
Union[None, Any]: Returns the data packets if |