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 following should not have been defined:
PX4_DIOC_GETPRIV
PX4_DEVIOCSPUBBLOCK
PX4_DEVIOCGPUBBLOCK
PX4_DEVIOCGDEVICEID
The actual defines are in drv_device.h and are:
DEVIOCSPUBBLOCK
DEVIOCGPUBBLOCK
DEVIOCGDEVICEID
DIOC_GETPRIV is defined by Nuttx, so mapped to SIOCDEVPRIVATE for POSIX
Signed-off-by: Mark Charlebois <charlebm@gmail.com>
Added more queue support to linux/px4_layer.
Use virt char devices for ms5611, and mavlink.
Added more HRT functionality. uORB latency test
now fails. Likely due to bad HRT impl for Linux.
Signed-off-by: Mark Charlebois <charlebm@gmail.com>
this device ID identifies a specific device via the tuple of (bus, bus
type, address, devtype). This allows device specific configuration
data to be stored along with a device ID, so the code can know when
the user has changed device configuration (such as removing an
external compass), and either invalidate the device configuration or
force the user to re-calibrate