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

DriverFramework purge #13900

Merged
merged 1 commit into from
Jan 13, 2020
Merged

DriverFramework purge #13900

merged 1 commit into from
Jan 13, 2020

Conversation

dagar
Copy link
Member

@dagar dagar commented Jan 9, 2020

No description provided.

@dagar
Copy link
Member Author

dagar commented Jan 10, 2020

Everything is working on a raspberry pi with navio2 shield.

pxh> ver all
HW arch: EMLID_NAVIO2
FW git-hash: 5dd475668cc45a628b88c9e9d3dd5c7eff1bd476
FW version: 1.11.0 80 (17498240)
FW git-branch: pr-DriverFramework_purge
OS: Linux
OS version: Release 4.19.83 (68375551)
Build datetime: Jan  9 2020 18:20:28
Build uri: localhost
Toolchain: GNU GCC, 8.3.0
PX4GUID: 100449495052303030443030303030303030
UNKNOWN MCU
pxh> sensors status
INFO  [sensors] gyro status:
INFO  [ecl/validation] validator: best: 1, prev best: 1, failsafe: NO (0 events)
INFO  [ecl/validation] sensor #0, prio: 75, state: OK
INFO  [ecl/validation] 	val:   0.3852, lp:   0.3831 mean dev:  -0.0003 RMS:   0.0266 conf:   1.0000
INFO  [ecl/validation] 	val:  -0.3398, lp:  -0.3378 mean dev:  -0.0005 RMS:   0.0240 conf:   1.0000
INFO  [ecl/validation] 	val:   0.0612, lp:   0.0905 mean dev:  -0.0003 RMS:   0.0196 conf:   1.0000
INFO  [ecl/validation] sensor #1, prio: 100, state: OK
INFO  [ecl/validation] 	val:  -0.0088, lp:  -0.0083 mean dev:  -0.0000 RMS:   0.0013 conf:   1.0000
INFO  [ecl/validation] 	val:  -0.0103, lp:  -0.0122 mean dev:   0.0000 RMS:   0.0013 conf:   1.0000
INFO  [ecl/validation] 	val:  -0.0015, lp:  -0.0017 mean dev:  -0.0000 RMS:   0.0014 conf:   1.0000
INFO  [sensors] accel status:
INFO  [ecl/validation] validator: best: 1, prev best: 1, failsafe: NO (0 events)
INFO  [ecl/validation] sensor #0, prio: 75, state: OK
INFO  [ecl/validation] 	val:  -1.0005, lp:  -0.9785 mean dev:  -0.0007 RMS:   0.0242 conf:   1.0000
INFO  [ecl/validation] 	val:  -0.0031, lp:   0.0304 mean dev:   0.0000 RMS:   0.0129 conf:   1.0000
INFO  [ecl/validation] 	val:  -9.3581, lp:  -9.3311 mean dev:  -0.0000 RMS:   0.0248 conf:   1.0000
INFO  [ecl/validation] sensor #1, prio: 100, state: OK
INFO  [ecl/validation] 	val:  -1.3825, lp:  -1.3865 mean dev:  -0.0001 RMS:   0.0096 conf:   1.0000
INFO  [ecl/validation] 	val:   0.0790, lp:   0.0763 mean dev:  -0.0000 RMS:   0.0097 conf:   1.0000
INFO  [ecl/validation] 	val:  -9.3336, lp:  -9.3419 mean dev:  -0.0002 RMS:   0.0145 conf:   1.0000
INFO  [sensors] mag status:
INFO  [ecl/validation] validator: best: 1, prev best: 1, failsafe: NO (0 events)
INFO  [ecl/validation] sensor #0, prio: 75, state: OK
INFO  [ecl/validation] 	val:  -0.4002, lp:  -0.4008 mean dev:   0.0002 RMS:   0.0032 conf:   1.0000
INFO  [ecl/validation] 	val:   0.2993, lp:   0.2982 mean dev:  -0.0008 RMS:   0.0042 conf:   1.0000
INFO  [ecl/validation] 	val:   0.4095, lp:   0.4092 mean dev:   0.0002 RMS:   0.0047 conf:   1.0000
INFO  [ecl/validation] sensor #1, prio: 100, state: OK
INFO  [ecl/validation] 	val:   0.2405, lp:   0.2543 mean dev:  -0.0008 RMS:   0.0088 conf:   1.0000
INFO  [ecl/validation] 	val:   0.4414, lp:   0.4318 mean dev:   0.0004 RMS:   0.0492 conf:   1.0000
INFO  [ecl/validation] 	val:   0.2691, lp:   0.2552 mean dev:   0.0003 RMS:   0.0083 conf:   1.0000
INFO  [sensors] baro status:
INFO  [ecl/validation] validator: best: 0, prev best: 0, failsafe: NO (0 events)
INFO  [ecl/validation] sensor #0, prio: 75, state: OK
INFO  [ecl/validation] 	val: 1024.2300, lp: 1024.2072 mean dev:   0.0053 RMS:   0.0619 conf:   1.0000
INFO  [ecl/validation] 	val:  40.6900, lp:  40.6726 mean dev:   0.0150 RMS:   0.0372 conf:   1.0000
INFO  [ecl/validation] 	val:   0.0000, lp:   0.0000 mean dev:   0.0000 RMS:   0.0000 conf:   1.0000
INFO  [sensors] Temperature Compensation:
INFO  [sensors]  gyro: enabled: 0
INFO  [sensors]  accel: enabled: 0
INFO  [sensors]  baro: enabled: 0
INFO  [sensors] Airspeed status:
INFO  [ecl/validation] 	no data
INFO  [vehicle_acceleration] selected sensor: 1
INFO  [vehicle_angular_velocity] selected sensor: 1
INFO  [vehicle_angular_velocity] using sensor_gyro_control: 2359554 (1)

@dagar dagar changed the title [WIP] DriverFramework purge DriverFramework purge Jan 10, 2020
@dagar dagar marked this pull request as ready for review January 10, 2020 02:30
@@ -1,42 +1,16 @@
uorb start
Copy link
Member

Choose a reason for hiding this comment

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

These eagle/excelsior configs are probably not very useful in their entirety anymore.

Copy link
Member Author

Choose a reason for hiding this comment

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

I want to get rid of posix-configs entirely soon.

@LorenzMeier
Copy link
Member

Bye bye!

@LorenzMeier
Copy link
Member

@dagar Something seems to be off for real here:

INFO  [px4] Calling startup script: /bin/sh etc/init.d-posix/rcS 0
102
INFO  [dataman] Unknown restart, data manager file './dataman' size is 11798680 bytes
103
INFO  [simulator] Waiting for simulator to connect on TCP port 4560
104
INFO  [simulator] Simulator connected on TCP port 4560.
105
ERROR [px4_work_queue] failed to create thread for wq:hp_default (1): Operation not permitted
106
ERROR [px4_work_queue] failed to create thread for wq:hp_default (1): Operation not permitted
107
ERROR [px4_work_queue] failed to create thread for wq:att_pos_ctrl (1): Operation not permitted
108
ERROR [commander] LED: open /dev/led0 failed
109
WARN  [commander] LED init failed
110
ERROR [px4_work_queue] failed to create thread for wq:hp_default (1): Operation not permitted
111
ERROR [px4_work_queue] failed to create wq:att_pos_ctrl
112
ERROR [px4_work_queue] wq:att_pos_ctrl not available
113
ERROR [px4_work_queue] init failed
114
ERROR [px4_work_queue] failed to create thread for wq:rate_ctrl (1): Operation not permitted

@dagar
Copy link
Member Author

dagar commented Jan 10, 2020

@dagar Something seems to be off for real here:

INFO  [px4] Calling startup script: /bin/sh etc/init.d-posix/rcS 0
102
INFO  [dataman] Unknown restart, data manager file './dataman' size is 11798680 bytes
103
INFO  [simulator] Waiting for simulator to connect on TCP port 4560
104
INFO  [simulator] Simulator connected on TCP port 4560.
105
ERROR [px4_work_queue] failed to create thread for wq:hp_default (1): Operation not permitted
106
ERROR [px4_work_queue] failed to create thread for wq:hp_default (1): Operation not permitted
107
ERROR [px4_work_queue] failed to create thread for wq:att_pos_ctrl (1): Operation not permitted
108
ERROR [commander] LED: open /dev/led0 failed
109
WARN  [commander] LED init failed
110
ERROR [px4_work_queue] failed to create thread for wq:hp_default (1): Operation not permitted
111
ERROR [px4_work_queue] failed to create wq:att_pos_ctrl
112
ERROR [px4_work_queue] wq:att_pos_ctrl not available
113
ERROR [px4_work_queue] init failed
114
ERROR [px4_work_queue] failed to create thread for wq:rate_ctrl (1): Operation not permitted

I believe that's the last "small" change I made to the work queue manager to not inherit priorities. My guess is something isn't right with the SCHED_RR change. I'll bring it in first separately so we can take a closer look.

@dagar dagar force-pushed the pr-DriverFramework_purge branch 2 times, most recently from 489b405 to 3ca70e0 Compare January 10, 2020 22:59
@dagar dagar force-pushed the pr-DriverFramework_purge branch 13 times, most recently from 387beff to c7cfbb1 Compare January 13, 2020 15:34
@dagar
Copy link
Member Author

dagar commented Jan 13, 2020

Quick test flight on a Navio2 - https://logs.px4.io/plot_app?log=6854d5e6-7061-4e19-a5f4-0336c707f5b0

All sensors (using in tree drivers) are working, including apply calibration through the formerly "NuttX" ioctl path.

pxh> param show CAL*
Symbols: x = used, + = saved, * = unsaved
x   CAL_ACC0_EN [26,67] : 1
x + CAL_ACC0_ID [27,68] : 1442050
x + CAL_ACC0_XOFF [28,69] : 0.1294
x + CAL_ACC0_XSCALE [29,70] : 1.0051
x + CAL_ACC0_YOFF [30,71] : 0.0795
x + CAL_ACC0_YSCALE [31,72] : 1.0008
x + CAL_ACC0_ZOFF [32,73] : 0.4059
x + CAL_ACC0_ZSCALE [33,74] : 0.9974
x   CAL_ACC1_EN [34,75] : 1
x + CAL_ACC1_ID [35,76] : 4457218
x + CAL_ACC1_XOFF [36,77] : 0.4475
x + CAL_ACC1_XSCALE [37,78] : 1.0114
x + CAL_ACC1_YOFF [38,79] : 0.0868
x + CAL_ACC1_YSCALE [39,80] : 1.0122
x + CAL_ACC1_ZOFF [40,81] : 0.2236
x + CAL_ACC1_ZSCALE [41,82] : 1.0031
x + CAL_ACC_PRIME [42,91] : 1442050
x   CAL_AIR_CMODEL [43,92] : 0
x   CAL_AIR_TUBED_MM [44,93] : 1.5000
x   CAL_AIR_TUBELEN [45,94] : 0.2000
x   CAL_BARO_PRIME [46,95] : 0
x   CAL_GYRO0_EN [47,96] : 1
x + CAL_GYRO0_ID [48,97] : 2359554
x + CAL_GYRO0_XOFF [49,98] : -0.0096
x + CAL_GYRO0_YOFF [50,99] : -0.0082
x + CAL_GYRO0_ZOFF [51,100] : -0.0028
x   CAL_GYRO1_EN [52,101] : 1
x + CAL_GYRO1_ID [53,102] : 4457218
x + CAL_GYRO1_XOFF [54,103] : 0.3476
x + CAL_GYRO1_YOFF [55,104] : -0.2605
x + CAL_GYRO1_ZOFF [56,105] : 0.0991
x + CAL_GYRO_PRIME [57,111] : 2359554
x   CAL_MAG0_EN [58,112] : 1
x + CAL_MAG0_ID [59,113] : 262402
x   CAL_MAG0_ROT [60,114] : -1
x + CAL_MAG0_XOFF [61,115] : 0.2008
x + CAL_MAG0_XSCALE [62,116] : 0.9794
x + CAL_MAG0_YOFF [63,117] : 0.2316
x + CAL_MAG0_YSCALE [64,118] : 1.0013
x + CAL_MAG0_ZOFF [65,119] : 0.0135
x + CAL_MAG0_ZSCALE [66,120] : 1.0178
x   CAL_MAG1_EN [67,121] : 1
x + CAL_MAG1_ID [68,122] : 4522498
x   CAL_MAG1_ROT [69,123] : -1
x + CAL_MAG1_XOFF [70,124] : 0.2331
x + CAL_MAG1_XSCALE [71,125] : 0.9535
x + CAL_MAG1_YOFF [72,126] : 0.2015
x + CAL_MAG1_YSCALE [73,127] : 1.0018
x + CAL_MAG1_ZOFF [74,128] : 0.1825
x + CAL_MAG1_ZSCALE [75,129] : 1.0437
x + CAL_MAG2_ID [76,131] : 0
x   CAL_MAG2_ROT [77,132] : -1
x + CAL_MAG3_ID [78,140] : 0
x   CAL_MAG3_ROT [79,141] : -1
x + CAL_MAG_PRIME [80,148] : 262402
x   CAL_MAG_SIDES [81,149] : 63
pxh> sensors status
INFO  [sensors] gyro status:
INFO  [ecl/validation] validator: best: 1, prev best: 1, failsafe: NO (0 events)
INFO  [ecl/validation] sensor #0, prio: 75, state: OK
INFO  [ecl/validation] 	val:   0.0300, lp:   0.0137 mean dev:  -0.0258 RMS:   0.0675 conf:   1.0000
INFO  [ecl/validation] 	val:  -0.0046, lp:  -0.0142 mean dev:   0.0199 RMS:   0.0525 conf:   1.0000
INFO  [ecl/validation] 	val:   0.0328, lp:   0.0134 mean dev:  -0.0075 RMS:   0.0263 conf:   1.0000
INFO  [ecl/validation] sensor #1, prio: 100, state: OK
INFO  [ecl/validation] 	val:   0.0002, lp:   0.0003 mean dev:   0.0006 RMS:   0.0020 conf:   1.0000
INFO  [ecl/validation] 	val:  -0.0002, lp:   0.0002 mean dev:   0.0006 RMS:   0.0019 conf:   1.0000
INFO  [ecl/validation] 	val:   0.0025, lp:   0.0006 mean dev:   0.0001 RMS:   0.0015 conf:   1.0000
INFO  [sensors] accel status:
INFO  [ecl/validation] validator: best: 1, prev best: 1, failsafe: NO (0 events)
INFO  [ecl/validation] sensor #0, prio: 75, state: OK
INFO  [ecl/validation] 	val:  -0.2072, lp:  -0.1936 mean dev:  -0.0380 RMS:   0.0913 conf:   1.0000
INFO  [ecl/validation] 	val:  -0.0481, lp:  -0.0616 mean dev:  -0.0071 RMS:   0.0234 conf:   1.0000
INFO  [ecl/validation] 	val:  -9.7983, lp:  -9.7703 mean dev:  -0.0350 RMS:   0.0485 conf:   1.0000
INFO  [ecl/validation] sensor #1, prio: 100, state: OK
INFO  [ecl/validation] 	val:  -0.2351, lp:  -0.2321 mean dev:  -0.0071 RMS:   0.0204 conf:   1.0000
INFO  [ecl/validation] 	val:  -0.0584, lp:  -0.0454 mean dev:  -0.0042 RMS:   0.0135 conf:   1.0000
INFO  [ecl/validation] 	val:  -9.8719, lp:  -9.8867 mean dev:  -0.0244 RMS:   0.0584 conf:   1.0000
INFO  [sensors] mag status:
INFO  [ecl/validation] validator: best: 1, prev best: 0, failsafe: NO (0 events)
INFO  [ecl/validation] sensor #0, prio: 75, state: OK
INFO  [ecl/validation] 	val:  -0.0076, lp:  -0.0060 mean dev:  -0.0020 RMS:   0.0036 conf:   1.0000
INFO  [ecl/validation] 	val:  -0.2549, lp:  -0.2534 mean dev:  -0.0029 RMS:   0.0041 conf:   1.0000
INFO  [ecl/validation] 	val:   0.3647, lp:   0.3753 mean dev:  -0.0017 RMS:   0.0095 conf:   1.0000
INFO  [ecl/validation] sensor #1, prio: 100, state: OK
INFO  [ecl/validation] 	val:   0.0193, lp:   0.0219 mean dev:  -0.0044 RMS:   0.0094 conf:   1.0000
INFO  [ecl/validation] 	val:  -0.2195, lp:  -0.2303 mean dev:   0.0050 RMS:   0.0561 conf:   1.0000
INFO  [ecl/validation] 	val:   0.3992, lp:   0.4026 mean dev:  -0.0039 RMS:   0.0096 conf:   1.0000
INFO  [sensors] baro status:
INFO  [ecl/validation] validator: best: 0, prev best: 0, failsafe: NO (0 events)
INFO  [ecl/validation] sensor #0, prio: 75, state: OK
INFO  [ecl/validation] 	val: 1021.1300, lp: 1021.1221 mean dev:   0.0140 RMS:   0.0681 conf:   1.0000
INFO  [ecl/validation] 	val:  40.2400, lp:  40.2131 mean dev:   0.0637 RMS:   0.0446 conf:   1.0000
INFO  [ecl/validation] 	val:   0.0000, lp:   0.0000 mean dev:   0.0000 RMS:   0.0000 conf:   1.0000
INFO  [sensors] Temperature Compensation:
INFO  [sensors]  gyro: enabled: 0
INFO  [sensors]  accel: enabled: 0
INFO  [sensors]  baro: enabled: 0
INFO  [sensors] Airspeed status:
INFO  [ecl/validation] 	no data
INFO  [vehicle_acceleration] selected sensor: 1
INFO  [vehicle_angular_velocity] selected sensor: 1
INFO  [vehicle_angular_velocity] using sensor_gyro_control: 2359554 (1)

Notes

  • terrible baro spikes (top mounted and directly exposed to the sun on a bright day, so not unexpected)
  • mediocre GPS, seems related to the mounting raspberry pi camera
  • lsm9ds1 gyro can develop a nasty bias (up to 0.3 radians/s) intermittently on the y axis
  • GPS is accessible on SPI1 (/dev/spidev0.0) which slightly interferes with IMU scheduling on the same bus (based on perf counters). This could probably be optimized in our GPS driver if anyone cared.

@dagar
Copy link
Member Author

dagar commented Jan 13, 2020

The bulk of this change was tightly coupled and needed to be deleted in one pass. Some of the smaller changes were things that broke as a result of the initial purge and subsequently fixed by further eradicating unnecessary platform differences. Finally, I deleted any dead code I came across in the related files I touched while going through everything.

  • DriverFramework (src/lib/DriverFramework submodule) completely removed
  • added dspal submodule in qurt platform (was brought in via DriverFramework)
  • all df wrapper drivers removed
  • all boards using df wrapper drivers updated to use in tree equivalents
  • unused empty arch/board.h on posix and qurt removed
  • unused IOCTLs removed (pub block, priv, etc)
  • Integrator delete methods only used from df wrapper drivers
  • commander: sensor calibration use "NuttX version" everywhere for now
  • sensors: update to px4_{open, read, close} instead of DevMgr wrapper (adc open for analog differential pressure)
  • battery_status: update to px4_{open, read, close} instead of DevMgr wrapper (adc open for analog differential pressure)
  • cdev cleanup conflicting typedefs and names with actual OS (pollevent_t, etc)
  • load_mon and top remove from linux boards (unused)
  • delete unused PX4_MAIN_FUNCTION
  • delete unused getreg32 macro
  • delete unused SIOCDEVPRIVATE define
  • named each platform tasks consistently
  • posix list_devices and list_topics removed (list_files now shows all virtual files)

The bulk of this change was tightly coupled and needed to be deleted in one pass. Some of the smaller changes were things that broke as a result of the initial purge and subsequently fixed by further eradicating unnecessary platform differences. Finally, I deleted any dead code I came across in the related files I touched while going through everything.

 - DriverFramework (src/lib/DriverFramework submodule) completely removed
 - added dspal submodule in qurt platform (was brought in via DriverFramework)
 - all df wrapper drivers removed
 - all boards using df wrapper drivers updated to use in tree equivalents
 - unused empty arch/board.h on posix and qurt removed
 - unused IOCTLs removed (pub block, priv, etc)
 - Integrator delete methods only used from df wrapper drivers
 - commander: sensor calibration use "NuttX version" everywhere for now
 - sensors: update to px4_{open, read, close} instead of DevMgr wrapper (adc open for analog differential pressure)
 - battery_status: update to px4_{open, read, close} instead of DevMgr wrapper (adc open for analog differential pressure)
 - cdev cleanup conflicting typedefs and names with actual OS (pollevent_t, etc)
 - load_mon and top remove from linux boards (unused)
 - delete unused PX4_MAIN_FUNCTION
 - delete unused getreg32 macro
 - delete unused SIOCDEVPRIVATE define
 - named each platform tasks consistently
 - posix list_devices and list_topics removed (list_files now shows all virtual files)
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