From 442b4787a0ed1f5c6ba8255b7a7058de046cdaa0 Mon Sep 17 00:00:00 2001
From: mbz <30321314+mbz4@users.noreply.github.com>
Date: Fri, 2 Dec 2022 22:58:40 +0200
Subject: [PATCH 1/3] update to imu docs
Expanded configuration to include manual workaround to IMU misaddressing & calibration bug.
Fixed typos and adjusted structure to improve overall information flow.
---
docs/parts/imu.md | 57 +++++++++++++++++++++++++++++++----------------
1 file changed, 38 insertions(+), 19 deletions(-)
diff --git a/docs/parts/imu.md b/docs/parts/imu.md
index 8659adab..e4759e46 100644
--- a/docs/parts/imu.md
+++ b/docs/parts/imu.md
@@ -10,31 +10,28 @@ MPU9250 offers additional integrated magnetometer.
* Typically uses the I2C interface and can be chained off the default PWM PCA9685 board. This configuration will also provide power.
* MPU6050: Outputs acceleration X, Y, Z, Gyroscope X, Y, Z, and temperature.
-* MPU6250: Outputs acceleration X, Y, Z, Gyroscope X, Y, Z, Magnetometer X, Y, Z and temperature.
+* MPU9250: Outputs acceleration X, Y, Z, Gyroscope X, Y, Z, Magnetometer X, Y, Z and temperature.
* Chip built-in 16bit AD converter, 16bit data output
* Gyroscopes range: +/- 250 500 1000 2000 degree/sec
* Acceleration range: ±2 ±4 ±8 ±16g
### Software Setup
-Install smbus
+Install smbus2
-* either from package:
+* either using pip:
``` bash
- sudo apt install python3-smbus
+ pip install smbus2
```
+* or conda:
-* or from source:
-
-```bash
-sudo apt-get install i2c-tools libi2c-dev python-dev python3-dev
-git clone https://github.com/pimoroni/py-smbus.git
-cd py-smbus/library
-python setup.py build
-sudo python setup.py install
+``` bash
+ conda install -c conda-forge smbus2
```
-For MPU6050:
+
+
+**If you are using MPU6050:**
Install pip lib for `mpu6050`:
@@ -42,7 +39,7 @@ Install pip lib for `mpu6050`:
pip install mpu6050-raspberrypi
```
-For MPU9250:
+**If you are using MPU9250:**
Install pip lib for `mpu9250-jmdev`:
@@ -51,18 +48,18 @@ pip install mpu9250-jmdev
```
### Configuration
-Enable the following configurations to your `myconfig.py`:
+1. Make the following configuration changes in your `/home/pi/mycar/myconfig.py`:
``` python
#IMU
HAVE_IMU = True
IMU_SENSOR = 'mpu9250' # (mpu6050|mpu9250)
-IMU_DLP_CONFIG = 3
+IMU_DLP_CONFIG = 0x05 # Digital Lowpass Filter setting (0x00:250Hz, 0x01:184Hz, 0x02:92Hz, 0x03:41Hz, 0x04:20Hz, 0x05:10Hz, 0x06:5Hz)
```
`IMU_SENSOR` can be either `mpu6050` or `mpu9250` based on the sensor you are using.
`IMU_DLP_CONFIG` allows to change the digital lowpass filter settings for your IMU. Lower frequency settings (see below) can filter high frequency noise at the expense of increased latency in IMU sensor data.
-Valid settings are from 0 to 6:
+Valid settings are from 0 (`0x00`) to 6 (`0x06`):
- `0` 250Hz
- `1` 184Hz
@@ -72,6 +69,28 @@ Valid settings are from 0 to 6:
- `5` 10Hz
- `6` 5Hz
+
+
+2. In `/home/pi/projects/donkeycar/donkeycar/parts/` find `imu.py`
+
+On lines `29`,`45` and `54` of `imu.py`, implement the following adjustments.
+
+* On line `29` change `addr=0x68` to `addr=0x69` (`...def __init__(self, addr=0x69, poll_delay=0.0166, ...`)
+
+* On line `45` change `address_mpu_slave=None` to `address_mpu_slave=0x0c`
+
+* On line `54` change `self.sensor.calibrateMPU6500()` to `#self.sensor.calibrateMPU6500()` (add `#` at the start of the line)
+
+
+
### Notes on MPU9250
-At startup the MPU9250 driver performs calibration to zero accel and gyro bias. Usually the process takes less than 10 seconds, and in that time avoid moving or touching the car.
-Please place the car on the ground before starting Donkey.
+If you are using Robohat MM1, the MPU9250 come presoldered and the following is applicable to you.
+The self-calibration routine currently does not function.
+This is why we comment out the corresponding line `54` in the second configuration step above.
+Factory calibration is thus considered as minimum sufficient.
+
+In case the calibration routine gets fixed in the future, the following applies:
+At startup the MPU9250 driver performs calibration to zero accel and gyro bias.
+Usually this process takes less than 10 seconds.
+Avoid moving or touching the car during this time.
+It is best to place the car on flat ground when first launching a driving script that relies on the imu.
From 4cd53abcf2863af83852218b8864a87c6ddc701d Mon Sep 17 00:00:00 2001
From: mbz <30321314+mbz4@users.noreply.github.com>
Date: Mon, 12 Dec 2022 15:31:29 +0100
Subject: [PATCH 2/3] modified to include IMU_ADDRESS
---
docs/parts/imu.md | 5 +++--
1 file changed, 3 insertions(+), 2 deletions(-)
diff --git a/docs/parts/imu.md b/docs/parts/imu.md
index e4759e46..b4d6db50 100644
--- a/docs/parts/imu.md
+++ b/docs/parts/imu.md
@@ -55,11 +55,12 @@ pip install mpu9250-jmdev
HAVE_IMU = True
IMU_SENSOR = 'mpu9250' # (mpu6050|mpu9250)
IMU_DLP_CONFIG = 0x05 # Digital Lowpass Filter setting (0x00:250Hz, 0x01:184Hz, 0x02:92Hz, 0x03:41Hz, 0x04:20Hz, 0x05:10Hz, 0x06:5Hz)
+IMU_ADDRESS = 0x69 # Please use i2c_detect to validate this address (0x68, 0x69, other; depends on your configuration)
```
`IMU_SENSOR` can be either `mpu6050` or `mpu9250` based on the sensor you are using.
`IMU_DLP_CONFIG` allows to change the digital lowpass filter settings for your IMU. Lower frequency settings (see below) can filter high frequency noise at the expense of increased latency in IMU sensor data.
-Valid settings are from 0 (`0x00`) to 6 (`0x06`):
+Valid settings are from 0 (`0x00`), 1 (`0x01`), ... to 6 (`0x06`):
- `0` 250Hz
- `1` 184Hz
@@ -75,7 +76,7 @@ Valid settings are from 0 (`0x00`) to 6 (`0x06`):
On lines `29`,`45` and `54` of `imu.py`, implement the following adjustments.
-* On line `29` change `addr=0x68` to `addr=0x69` (`...def __init__(self, addr=0x69, poll_delay=0.0166, ...`)
+* On line `29` change `addr=0x68` to IMU_ADDRESS` (`...def __init__(self, addr=IMU_ADDRESS, poll_delay=0.0166, ...`)
* On line `45` change `address_mpu_slave=None` to `address_mpu_slave=0x0c`
From 0317bb4492b8b910ab7dec190e78d65535302d10 Mon Sep 17 00:00:00 2001
From: mbz <30321314+mbz4@users.noreply.github.com>
Date: Mon, 12 Dec 2022 15:33:25 +0100
Subject: [PATCH 3/3] fixed missing character
---
docs/parts/imu.md | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/docs/parts/imu.md b/docs/parts/imu.md
index b4d6db50..75782f82 100644
--- a/docs/parts/imu.md
+++ b/docs/parts/imu.md
@@ -76,7 +76,7 @@ Valid settings are from 0 (`0x00`), 1 (`0x01`), ... to 6 (`0x06`):
On lines `29`,`45` and `54` of `imu.py`, implement the following adjustments.
-* On line `29` change `addr=0x68` to IMU_ADDRESS` (`...def __init__(self, addr=IMU_ADDRESS, poll_delay=0.0166, ...`)
+* On line `29` change `addr=0x68` to `IMU_ADDRESS` (`...def __init__(self, addr=IMU_ADDRESS, poll_delay=0.0166, ...`)
* On line `45` change `address_mpu_slave=None` to `address_mpu_slave=0x0c`