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

Fix driver load order for external ICM20948/Here GNSS for Pixhawk Cube #11189

Closed
wants to merge 1 commit into from

Conversation

flochir
Copy link
Contributor

@flochir flochir commented Jan 10, 2019

With the driver load in rc.sensors, the external ICM20948 magnetometer on Here GNSS gets activated as last (and 4th) magnetometer on Pixhawk Cube. It gets set as primary mag after calibration, but QGroundControl does not show the "External Compass Orientation" Dropdown in Parameters -> Sensors -> Set Orientations:

here_gnss_orientations

I moved the driver load to the start of rc.board of px4fmu-v3, after the load of external ist8310. This resolves the issue for Pixhawk Cube.

@flochir
Copy link
Contributor Author

flochir commented Jan 10, 2019

@DanielePettenuzzo @dagar @dakejahl This does not fix the issue for other boards though, not sure which to add it to. I noticed e.g. ist8310 gets loaded in various rc.board's. Is there some better place to load an external driver, like rc.sensors, but before rc.board runs?

@dagar
Copy link
Member

dagar commented Jan 11, 2019

I'd rather we try to fix the underlying issue than to have to juggle startup ordering.

What's being published in each scenario? What are the existing parameters? Is it being correctly detected as external?

nsh> listener sensor_mag -i 0
nsh> listener sensor_mag -i 1
nsh> listener sensor_mag -i 2
nsh> listener sensor_mag -i 3

nsh> param show CAL_MAG*

@dagar dagar requested review from dagar and dakejahl January 11, 2019 15:17
@dagar dagar added the bug label Jan 11, 2019
@dagar dagar added this to the Release v1.9.0 milestone Jan 11, 2019
@dagar
Copy link
Member

dagar commented Jan 11, 2019

Related #11190

@flochir
Copy link
Contributor Author

flochir commented Jan 11, 2019

@dagar There's no underlying issue to this in the mpu9250 driver. I cross-tested with a Pixhawk 4 GPS (ist8310 Magnetometer) and it has the same problem when the driver load is moved to rc.sensors. The issue is solved if the mpu9250 driver for external I2C is loaded in the same place as ist8310, at the beginning of rc.board.

@flochir
Copy link
Contributor Author

flochir commented Jan 11, 2019

@dagar Btw. both external mags, ICM20948 and ist8310, are recognized as external mags and are set as CAL_MAG_PRIME even if activated as last in order. But they still don't show up in QGroundcontrol and their orientation can't be set.

@dagar
Copy link
Member

dagar commented Jan 11, 2019

Then it's likely something on the QGC side.

@@ -47,6 +47,9 @@ hmc5883 -C -T -X start
lis3mdl -X start
ist8310 -C start

# ICM20948 as external magnetometer on I2C (with Rotation 6 for Here GNSS)
mpu9250 -X -M -R 6 start
Copy link
Member

Choose a reason for hiding this comment

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

Side question, is the icm20948 actually mounted at yaw 270 in the Here GNSS or is this also accounting for rotations in the driver itself?

Copy link
Contributor Author

@flochir flochir Jan 11, 2019

Choose a reason for hiding this comment

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

Edit (short answer): Yes, it's mounted yaw270 in the Here GNSS.
Sorry, misread your question a bit first.

@dakejahl
Copy link
Contributor

dakejahl commented Jan 11, 2019

I don't have this issue, we only use a single mag. As a side note however, I do know that the driver startup order does matter for selecting the primary imu. This matters because whichever imu is started first becomes instance 0 with respect to CAL_GYRO0_EN/CAL_ACC0_EN. Obviously you can still specify the primary imu with CAL_GYRO_PRIME/CAL_ACC_PRIME, but if you want to turn off the gyro/accel from an imu, you need to know which order it was started in. For example, our 6500 is hard mounted to our PCB, so we don't want that data used at all because it is incredibly noisy and the flight controller cannot control around it (we've tried, it goes nuts). So I need to start the 6500 second, since I specify

param set CAL_GYRO1_EN 0
param set CAL_ACC1_EN 0

Haha sorry this is a little tangent to the topic at hand, but I felt it was at least a little relevant and good to know.

@flochir
Copy link
Contributor Author

flochir commented Jan 11, 2019

No, thanks for the comment! Just gave me an idea for an issue I need to test out :)

@flochir
Copy link
Contributor Author

flochir commented Jan 13, 2019

@dagar
Below are the requested outputs.
However e.g. here's an excerpt of rc.board for px4fmu-v4:

...
# Possible external compasses
hmc5883 -C -T -X start

# Possible external compasses
ist8310 -C -b 1 start
ist8310 -C -b 2 start

# Possible internal compass
ist8310 -C -b 5 start
...

Of course it would be nice if QGroundcontrol would handle the 4th sensor correctly, but until then I think the Here GNSS should not be handled differently than the other external mags if it causes this problem.

nsh> listener sensor_mag -i 0

TOPIC: sensor_mag instance 0 #1
 sensor_mag_s
        timestamp: 135121467  (0.007368 seconds ago)
        error_count: 0
        device_id: 263202 (Type: 0x04, SPI:4 (0x04)) 
        x: 0.0068
        y: -0.1470
        z: 0.3915
        temperature: 46.2793
        scaling: 0.0015
        x_raw: 48
        y_raw: 148
        z_raw: 410
        is_external: False

nsh> listener sensor_mag -i 1

TOPIC: sensor_mag instance 1 #1
 sensor_mag_s
        timestamp: 193110713  (0.008896 seconds ago)
        error_count: 0
        device_id: 131618 (Type: 0x02, SPI:4 (0x02)) 
        x: 0.0079
        y: -0.1600
        z: 0.4149
        temperature: 44.1250
        scaling: 0.0001
        x_raw: 1254
        y_raw: -676
        z_raw: 4960
        is_external: False

nsh> listener sensor_mag -i 2

TOPIC: sensor_mag instance 2 #1
 sensor_mag_s
        timestamp: 207276488  (0.001479 seconds ago)
        error_count: 0
        device_id: 263178 (Type: 0x04, SPI:1 (0x04)) 
        x: -0.0474
        y: -0.1403
        z: 0.3905
        temperature: 47.5253
        scaling: 0.0015
        x_raw: 216
        y_raw: -176
        z_raw: -96
        is_external: False

nsh> listener sensor_mag -i 3

TOPIC: sensor_mag instance 3 #1
 sensor_mag_s
        timestamp: 219665735  (0.008200 seconds ago)
        error_count: 0
        device_id: 289033 (Type: 0x04, I2C:1 (0x69)) 
        x: -0.0345
        y: -0.2190
        z: 0.3885
        temperature: 21.0000
        scaling: 0.0015
        x_raw: 23
        y_raw: 146
        z_raw: 259
        is_external: True

nsh> param show CAL_MAG*
Symbols: x = used, + = saved, * = unsaved
x + CAL_MAG0_EN [70,85] : 1
x + CAL_MAG0_ID [71,86] : 263202
x + CAL_MAG0_ROT [72,87] : -1
x + CAL_MAG0_XOFF [73,88] : -0.0931
x + CAL_MAG0_XSCALE [74,89] : 1.0089
x + CAL_MAG0_YOFF [75,90] : -0.1212
x + CAL_MAG0_YSCALE [76,91] : 1.0015
x + CAL_MAG0_ZOFF [77,92] : 0.3172
x + CAL_MAG0_ZSCALE [78,93] : 0.9879
x + CAL_MAG1_EN [79,94] : 0
x + CAL_MAG1_ID [80,95] : 131618
x + CAL_MAG1_ROT [81,96] : -1
x + CAL_MAG1_XOFF [82,97] : -0.0622
x + CAL_MAG1_XSCALE [83,98] : 0.9753
x + CAL_MAG1_YOFF [84,99] : 0.0631
x + CAL_MAG1_YSCALE [85,100] : 0.9794
x + CAL_MAG1_ZOFF [86,101] : 0.0019
x + CAL_MAG1_ZSCALE [87,102] : 1.0508
x + CAL_MAG2_EN [88,103] : 0
x + CAL_MAG2_ID [89,104] : 263178
x   CAL_MAG2_ROT [90,105] : -1
x + CAL_MAG2_XOFF [91,106] : 0.3618
x + CAL_MAG2_XSCALE [92,107] : 1.0261
x + CAL_MAG2_YOFF [93,108] : -0.2431
x + CAL_MAG2_YSCALE [94,109] : 0.9651
x + CAL_MAG2_ZOFF [95,110] : -0.2204
x + CAL_MAG2_ZSCALE [96,111] : 1.0093
x + CAL_MAG3_EN [97,112] : 0
x + CAL_MAG3_ID [98,113] : 289033
x + CAL_MAG3_ROT [99,114] : 0
  + CAL_MAG3_XOFF [-1,115] : -0.0637
  + CAL_MAG3_XSCALE [-1,116] : 1.0410
  + CAL_MAG3_YOFF [-1,117] : -0.0461
  + CAL_MAG3_YSCALE [-1,118] : 0.9684
  + CAL_MAG3_ZOFF [-1,119] : -0.0463
  + CAL_MAG3_ZSCALE [-1,120] : 0.9929
x + CAL_MAG_PRIME [100,121] : 289033
x + CAL_MAG_SIDES [101,122] : 63

 1243 parameters total, 760 used.

@dagar
Copy link
Member

dagar commented Jan 14, 2019

Let's get this in after #11044 is merged.

@stale
Copy link

stale bot commented Oct 13, 2019

This issue has been automatically marked as stale because it has not had recent activity. Thank you for your contributions.

@dagar
Copy link
Member

dagar commented Aug 14, 2020

No longer an issue (we don't use the mpu9250 mags by default).

@dagar dagar closed this Aug 14, 2020
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants