Commit Graph

305 Commits

Author SHA1 Message Date
Beat Küng 4088c2581f
i2c_spi_buses: add '-q' for quiet startup flag (#14969)
* [WIP] i2c_spi_buses: add '-q' for quiet startup flag

And enable for optional board sensors.

* ROMFS: rc.sensors try starting all optional I2C sensors quietly

Co-authored-by: Daniel Agar <daniel@agar.ca>
2020-08-26 08:46:35 +02:00
Daniel Agar ad3e6ee5dd
wq:attitude_ctrl increase stack by 16 bytes (again) 2020-08-16 18:16:16 -04:00
David Sidrane 13246bdb2c common/shutdown:All FMU's not stying in bootloader
Fixes bug, wehre reboot -b would not stay in bootloader.
   Call was passing bit mask (=4) not integer value of 1.
2020-08-14 14:11:45 +02:00
Daniel Agar 0c91a29c3f wq:attitude_ctrl increase stack 2020-08-13 13:32:07 -04:00
Daniel Agar b6a17a6538
new IntrusiveSortedList container used for uORB, WorkQueues, and WorkItems
- new intrusive linked list container (c++ template) that sorts on insertion
 - primarily for convenience inspecting things in the system like uORB or WorkQueues
 - uorb status or top sorted alphabetically 
 - work_queue status threads sorted by priority, then items sorted alphabetically within each
2020-08-04 11:09:41 -04:00
Daniel Agar b54dea0ccd wq:attitude_ctrl: small stack increase to silence warning 2020-07-17 19:51:48 -04:00
Daniel Agar fa44cd5cd5 px4_work_queue: rename navigation_and_controllers -> nav_and_controllers
- keep the thread within the current NuttX max length
2020-07-14 09:48:47 -04:00
Daniel Agar 0eea814ca1 decrease all wq:SPIx stack 2020-06-18 20:49:15 -04:00
Daniel Agar be2081a2a2 wq:attitude_ctrl small stack increase 2020-06-18 01:36:29 -04:00
Daniel Agar 13e34b32e6 new Bosch BMI088 IMU driver using FIFOs and DRDY 2020-06-11 12:25:13 -04:00
Daniel Agar ff3b040d3c imu/invensense/icm20608g: minor improvements and potential fixes
- perform full sensor signal path reset and wait for max time (100 ms)
 - issue full sensor reset on any error
 - always read FIFO count before transfersj
 - only allocate drdy perf counter if GPIO is available
2020-06-05 21:28:37 -04:00
Daniel Agar 31fe7af454 selectively increase optimization -Os -> -O2
- targetted at modules/libraries that benefit without drastically
increasing flash usage
 - ignored on boards with CONSTRAINED_FLASH set
2020-06-04 20:59:52 -04:00
Julian Oes 1cb706c411 px4_log: flush each line
Without this fix all PX4 output is buffered and presented at the very
end of a scripted MAVSDK test which makes the log hard to read.
2020-05-29 11:46:14 +02:00
Daniel Agar 8ee0a5d328 px4_work_queue: minor status changes
- only record start time on first run rather than init
 - increase name length
 - round average interval to nearest microsecond
 - basic formatting consistency (google style guide)
2020-05-23 11:51:23 -04:00
Matthias Grob a605444462 board_comnmon: indent BOARDBRICK_VALID_LIST to correct level
to avoid other people getting confused as well.
2020-05-18 10:52:26 -04:00
Matthias Grob 22cdf80293 i2c_spi_buses.h: work around astyle version inconsistency 2020-05-14 08:32:07 +02:00
Daniel Agar 746a8f5cf9 commander: reboot/shutdown usability fixes
- always check with state machine before reboot/shutdown
 - respect BOARD_HAS_POWER_CONTROL (shutdown from command, low battery, power button)
 - px4_shutdown_request add optional delay and always execute from HPWORK
 - px4_shutdown_request split out px4_reboot_request
2020-05-06 13:53:54 -04:00
Daniel Agar 682aa700bb px4_work_queue: increase wq:attitude_ctrl stack 2020-05-05 12:53:18 -04:00
Daniel Agar 326d8efc16 move attitude controllers to new wq:attitude_ctrl 2020-04-27 21:34:35 -04:00
Beat Küng d3dd5e9da1 i2c_spi_buses: improve info output for external buses 2020-04-24 12:59:50 +02:00
Daniel Agar a3ad710623
restore UAVCAN bootloader support
- essentially reverting #7878 minus the obsolete board support
2020-04-19 16:10:09 -04:00
mcsauder 6548fde024 Whitespace cleanup to quiet new blank line at EOF git hook. 2020-04-15 23:00:39 -04:00
Daniel Agar 66eacd24bc
px4_fmu-v5_stackcheck: update stack sizes and add to Jenkins
- increase stack sizes to run cleanly under stackcheck
     - this is likely overkill for most boards, but using stackcheck to set our minimum ensures we have a very safe margin on regular builds and it's something we can currently afford
 - remove holybro_durandal-v1_stackcheck from test rack (there's only one unit)
2020-04-11 21:16:10 -04:00
Jacob Dahl d682ddb510
UAVCAN differential pressure sensor support
* added airspeed handling (differential pressure) to uavcan and uavcannode

Co-authored-by: Jacob Crabill <jacob@flyvoly.com>
2020-04-07 00:15:31 -04:00
AlexKlimaj d8c140be04
UAVCAN Smart Battery Improvements 2020-04-06 21:09:02 -04:00
Daniel Agar ad559a66a1 examples: add simple work_item example module 2020-04-06 09:43:55 -04:00
Daniel Agar 1d164c0dbd px4_work_queue: sem_wait add loop as the wait may be interrupted by a signal 2020-04-06 10:30:35 +02:00
Beat Küng a556a44a57 i2c_spi_buses: print an error if a driver does not pass the I2C address 2020-03-30 15:55:24 -04:00
Daniel Agar efceccd91d posix: micro_hal.h add empty px4_arch_gpiosetevent to build new Invensense drivers on linux 2020-03-25 01:05:38 -04:00
Daniel Agar 404e781cd9 px4_work_queue: increase SPI stack uniformly to silence warnings 2020-03-25 01:05:38 -04:00
Beat Küng 6ad5357d1a SPI+I2C: remove unused defines and printf's 2020-03-24 09:46:20 -04:00
Daniel Agar 8738c26426
boards: enable NuttX SPI DMA buffers
- update to NuttX with stm32f4 and stm32f7 SPI DMA internal buffers
 - remove explicit DMA buffer allocations from new IMU drivers
 - restore original BOARD_DMA_ALLOC_POOL_SIZE
 - decrease SPI DMA thresholds based on fmu-v2/v3/v4/v5 bench testing
2020-03-22 19:24:26 -04:00
SalimTerryLi dc8e775d8f
ADC: replace ioctl with uorb message (#14087) 2020-03-20 11:23:32 +01:00
Beat Küng d6bb5b3b9e i2c spi buses: enforce drivers to set default SPI/I2C bus frequency
Not a lot of drivers use the global default, which is somewhat arbitrary.
2020-03-17 23:31:17 -04:00
Beat Küng a6ddf0e4b9 refactor sf1xx: use driver base class 2020-03-17 23:31:17 -04:00
Beat Küng dbb53044ce refactor ms5611: use driver base class
Also: remove device type auto-detection as it will not work with
together with the new SPI board config (which specifies a specific
device type)
2020-03-17 23:31:17 -04:00
Beat Küng 83b6f6456b refactor I2CSPIInstance: store running instances in a global linked list
instead of a static per-driver array.

Reduces BSS RAM usage by a couple of 100 Bytes (linear increase with num
drivers).

Downsides:
- a bit more runtime overhead
- less isolation, locking required
- a bit more complex
2020-03-17 23:31:17 -04:00
Beat Küng e7f04109d9 i2c spi init + custom methods: use WorkItemSingleShot
Use it for custom methods as well (like reset), and run by default on the
work queue, since they typically access the bus.
2020-03-17 23:31:17 -04:00
Beat Küng 8c41025565 px4_work_queue: add WorkItemSingleShot
To run a specific method on a work queue and wait for it to return.
2020-03-17 23:31:17 -04:00
Beat Küng 134413233a i2c spi: extend BusCLIArguments to handle common driver arguments 2020-03-17 23:31:17 -04:00
Beat Küng d1f5b23a5a module docs: add PRINT_MODULE_USAGE_PARAMS_I2C_{SPI_DRIVER,ADDRESS}
For SPI/I2C driver default options
2020-03-17 23:31:17 -04:00
Beat Küng f851f65f8d i2c spi: add type to I2CSPIInstance
Needed to distinguish runtime instance types of the same driver (e.g.
bmi055 accel vs gyro).
2020-03-17 23:31:17 -04:00
Matthias Grob 2dccc0dcfc posix.h: remove duplicate stdint.h include 2020-03-12 17:49:37 +00:00
David Sidrane 82ab1413fc px4_fmu-v5:Add Manifest Entries for UAVCAN interfaces 2020-03-11 20:36:58 -04:00
Daniel Agar 9cd8bb4f88
sensors: move to WQ
Running the sensors module out of the same WQ thread as the estimator, position, and attitude controllers is a bit safer and prevents potential priority and starvation issues. There is a very small increase in latency (~50 us) between sensors and ekf2 execution (on average). This also saves a little bit of memory (~ 3 kB) and cpu (~1-1.5% depending on the board).
2020-03-11 11:34:04 -04:00
Daniel Agar 9585055e9e
uORB: add bitset for faster orb_exists check and remove uORB::Subscription lazy subscribe hack/optimization
- add PX4 bitset and atomic_bitset with testing
 - add uORB::Subscription constructor to take ORB_ID enum
 - move orb test messages into msg/
2020-03-11 09:06:33 -04:00
Beat Küng 1851665fab boards: add new spi+i2c config
Chip-select and SPI initialization uses the new config, whereas the drivers
still use the existing defines.

The configuration in board_config.h can be removed after all drivers are
updated.
2020-03-10 10:11:43 -04:00
Beat Küng 06712450a7 i2c+spi: add module base class and bus iterators 2020-03-10 10:11:43 -04:00
Beat Küng 18bc6cf872 ScheduledWorkItem::ScheduleClear: remove item from runnable queue
The existing behavior is unexpected: if the work item is already on the
runnable queue, it will still be triggered after a call to ScheduleClear().
This can lead to race conditions.
2020-03-09 08:06:00 -04:00
David Sidrane ee220a5086 px4_fmuv5x:Update manifest for USB not present 2020-03-02 19:59:36 -05:00
TSC21 993755b24b bitmask.h: compile only if in POSIX/LINUX platforms 2020-02-28 10:59:50 +00:00
TSC21 f5000a9691 px4_platform_common: add bitmask.h for templated type safe bitmask operations 2020-02-28 10:59:50 +00:00
SalimTerryLi 77a9135036
ADC driver report back vref alone with sample count (#14136)
* Introduce "px4_arch_adc_reference_v"

* Revert "Introduce "px4_arch_adc_reference_v""

This reverts commit 93691fbbd55a1b8da8c190e225b318067d90399b.

* use structure to return sample count and vref at the same time

* Revert "use structure to return sample count and vref at the same time"

This reverts commit 9cfd1c173cda51495f766a3f678c2202d67725fd.

* Revert "Revert "Introduce "px4_arch_adc_reference_v"""

This reverts commit edb7f7603e4471163ffb0fc6fc62ad2e30336e91.

* fix missed reference

* remove unecessary channel specific vref

* Update src/drivers/drv_adc.h

Co-Authored-By: David Sidrane <David.Sidrane@Nscdg.com>

* Update src/drivers/drv_adc.h

Co-Authored-By: David Sidrane <David.Sidrane@Nscdg.com>

* Introduce BOARD_ADC_POS_REF_V

Co-authored-by: David Sidrane <David.Sidrane@Nscdg.com>
2020-02-21 06:52:45 -08:00
Daniel Agar 22499effb9 invensense icm20602 improvements
- checked register mechanism and simple watchdog
    - driver checks for errors gradually and can reconfigure itself
 - respect IMU_GYRO_RATEMAX at the driver level
 - fixed sensor INT16_MIN and INT16_MAX handling (y & z axis are flipped before publishing)
 - increased sensor_gyro_fifo max size (enables running the driver much slower, but still transferring all raw data)
 - PX4Accelerometer/PX4Gyroscope remove unnecessary memsets
2020-02-18 19:21:20 -05:00
Julian Oes cf47c2155f
platforms: prevent stackoverflow for ekf2 sideslip
It turns out that ekf2 needs more stack when sideslip fusion fails.
Sideslip fusion is currently only enabled for fixedwing by default and
not executed in testing.
2020-02-18 16:42:16 -05:00
Daniel Agar d7c3e1066a
uavcannode updates and px4_fmu-v4_cannode example
- drivers/uavcannode add baro, mag, gps publications
 - delete old px4_cannode-v1 board
 - add stripped down simple rcS for CAN nodes
2020-02-16 12:11:54 -05:00
Beat Küng 3217b539c6 px4_arch: add hw description constexpr util methods
These will be used in the board configurations.
2020-02-13 03:49:16 -08:00
David Sidrane 80ac80b5e4 s32k1xx:Add stubbed out chip and arch 2020-02-12 10:29:27 -05:00
SalimTerryLi e0abe7090e
SBUS on Linux: replace termios with termios2 and add UNKNOWN UART WQ 2020-02-02 14:06:27 -05:00
David Sidrane 490fe8256f Add nxp imxrt device support 2020-01-29 13:54:20 -05:00
Daniel Agar 24f0c2d72a
sensors: move gyro filtering to sensors/vehicle_angular_velocity
- gyro filtering (low-pass and notch) only performed on primary gyro in `sensors/vehicle_angular_velocity` instead of every gyro in `PX4Gyroscope`
 - sample rate is calculated from actual updates (the fixed value was slightly wrong in many cases, and very wrong in a few)
 - In the FIFO case the array is now averaged and published in `sensor_gyro` for filtering downstream. I'll update this in the future to use the full FIFO array (if available), but right now it should be fine.
2020-01-27 10:05:33 -05:00
Julian Oes 30188d2884 Revert "Simulation: Set scheduling policy RR for lockstep"
This reverts commit 742b1839d5.
2020-01-24 12:04:47 +01:00
Daniel Agar 21a8d7db7f WorkItem modules: Run() shouldn't be public 2020-01-22 12:03:03 -05:00
Daniel Agar dc05ceaad2
create temperature_compensation module
- this is a new module for temperature compensation that consolidates the functionality previously handled in the sensors module (calculating runtime thermal corrections) and the events module (online thermal calibration)
 - by collecting this functionality into a single module we can optionally disable it on systems where it's not used and save some flash (if disabled at build time) or memory (disabled at run time)
2020-01-20 21:42:42 -05:00
Daniel Agar de4f594937 DriverFramework purge
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)
2020-01-13 14:07:03 -05:00
Daniel Agar 756b0148d6
platforms: split posix hrt for qurt
- this keeps the per platform libraries contained to their respective directories and minimizes the ifdef mess
2020-01-12 22:09:34 -05:00
Daniel Agar d1e3ff553b platforms: remove unnecessary i2c platform abstraction 2020-01-11 11:55:06 -05:00
Daniel Agar bd111c9f42
px4_work_queue: revert inherited sched attr and run wq:manager and max priority
Setting PTHREAD_EXPLICIT_SCHED was necessary on linux to create WQ threads with priorities relative to max, but unfortunately we can't rely pthread_attr_setinheritsched as it's dependent on system ulimit configuration or running privileged. Instead we can create the wq:manager at the maximum desired priority and allow each WQ thread to have a relative priority.
2020-01-10 17:57:51 -05:00
Daniel Agar a08b54b8e1
px4_work_queue: don't inherit pthread attributes from creating thread
- this is necessary on linux so that the WQ threads priorities are set relative to max, and not relative to the wq:manager thread
2020-01-10 11:02:49 -05:00
Daniel Agar 23e17aec42
atlflight/eagle: minor fixes to get it running again
- fixed df_ltc2946_wrapper battery dependency
 - fixed px4::atomic fetch_add for QuRT
 - updated PX4 QuRT SPI wrapper to set bus frequency
 - renamed "qurt-default" configs to just "qurt"
2020-01-09 18:09:06 -05:00
Daniel Agar 44f9de5e37
delete parrot bebop board support
This target was never fully supported and is heavily dependent on a number of DriverFramework drivers that have no in tree equivalents (bebop bus, flow, rangefinder, etc). Deleting this will make it easier to fully drop DriverFramework shortly.
2020-01-05 19:46:51 -05:00
Lorenz Meier 742b1839d5 Simulation: Set scheduling policy RR for lockstep
This should ensure that all processes do still run at full load.
2019-12-26 10:16:58 +01:00
Daniel Agar 1d3f722201
px4_work_queue: increase hp_default stack 1800 -> 1900 bytes 2019-12-09 12:41:11 -05:00
David Sidrane cada41f027 WorkQueueManager:Fix low stack warning introduced by stism330 2019-12-03 16:16:49 -05:00
Daniel Agar 071f159794 PX4 work queue: extend to UARTs 2019-11-27 20:44:32 -05:00
Daniel Agar 2811307293 px4_work_queue: increase wq:hp_default stack 1500->1800 bytes (found by stackcheck) 2019-11-23 17:23:30 -05:00
Beat Küng 1371887578 board config: add define for adc voltage scaling 2019-11-21 08:19:59 +01:00
Daniel Agar 99aae8b891 NuttX use toolchain math.h and avoid empty drivers/Kconfig 2019-11-16 11:43:42 +01:00
David Sidrane e847698c9f PX4 System changes Supporting STM32H7
stm32:ToneAlarmInterfacePWM TIM15-TIM17 have a BDTR Register

common:board_crashdump Add H7 support

stm32/board_mcu_version:Support H7

PX4 ADC:Use 32 interface and resoution abstraction

Added PX4 stm32h7 ADC driver

stm32h7:adc fix ADC ready check

fmu: handle BOARD_HAS_PWM==5

cmake: improve error handling for NuttX olddefconfig failures

WorkQueueManager:Quiet loadmon stack warning

camera_trigger:GPIO support < 6 GPIO

Adjust stack sizes (under hw stack check)

PX4 System changes Supporting STM32H7 PX4IO Driver

aerotenna_ocpoc:ADC add px4_arch_adc_dn_fullcount

init.cmake:Track Upstream change needing Make.def at config time

PX4 System changes Supporting STM32H7

NuttX CMakeLists.txt Track upstream changes

Common board_crashdump add header and px4 config

NuttX simplify callinb make libapps

Use UINT32_MAX for error return

drivers:uavcannode NuttX chip is now hardware

drivers:uavcanesc NuttX chip is now hardware

px4io:Avoid Race on AP to PX4 IO upgrade
2019-11-16 11:43:42 +01:00
Daniel Agar c5520cbaca mpu9250: start building "NuttX" driver for Linux and QuRT 2019-11-13 09:21:02 -05:00
Daniel Agar 1c4e854f93 cmake don't build param "c" files and remove param defines
- these aren't actual source code
2019-11-11 10:25:42 -05:00
Beat Küng 5dff065ec5 uavcan: move to work queue and use MixingOutput
Main UAVCAN protocol handling and ESC updates run on the same thread/wq as
before. There are 2 WorkItems for separate scheduling of the 2, so that
ESC updates run in sync with actuator_control updates. UAVCAN is scheduled
at a fixed rate of 3ms (previously the poll timeout) and on each UAVCAN
bus event.
This leads to roughly the same behavior as before. CPU & RAM usage are
pretty much the same (tested on Pixhawk 4).

Testing done: Motors still work (with feedback), param changes and a
UAVCAN optical flow sensor.
2019-11-07 10:40:03 +01:00
Beat Küng a203475489 BlockingList: fix unsafe getLockGuard() API
getLockGuard relies on copy elision to work correctly, which the compiler
is not required to do (only with C++17).
If no copy elision happens, the mutex ends up being unlocked twice, and the
CS is executed with the mutex unlocked.

The patch also ensures that the same pattern cannot be used again.
2019-11-05 12:14:20 +01:00
Daniel Agar 69bec3ee62
defines.h delete obsolete PRIu64, PRId64, and offsetof 2019-11-03 11:50:15 -05:00
Daniel Agar 7bf9700426
NuttX: math.h drop extra math defines carried in PX4 defines.h 2019-11-03 10:30:00 -05:00
FlavioTonelli 7984c0c910 px4_work_queue: stack size rounded to page size on posix 2019-11-03 09:04:04 -05:00
Matthias Grob 933ff8d480 Remove duplicate EOF trailing newlines
because they can screw up git when merging branches.
2019-11-02 09:49:46 -04:00
Beat Küng e7519c9fa0 board_identity: move to platforms/nuttx/src
And fix a potential alignment issue in board_get_mfguid and
board_get_px4_guid.
2019-10-30 11:48:47 +01:00
Beat Küng b30171ba8d board_common.h: move under platforms/common
Also move board_determine_hw_info and board_gpio_init under platforms/nuttx
2019-10-30 11:48:47 +01:00
Beat Küng 3198610f85 src/platforms: move all headers to platforms/common/include/px4_platform_common
and remove the px4_ prefix, except for px4_config.h.

command to update includes:
for k in app.h atomic.h cli.h console_buffer.h defines.h getopt.h i2c.h init.h log.h micro_hal.h module.h module_params.h param.h param_macros.h posix.h sem.h sem.hpp shmem.h shutdown.h tasks.h time.h workqueue.h; do for i in $(grep -rl 'include <px4_'$k src platforms boards); do sed -i 's/#include <px4_'$k'/#include <px4_platform_common\/'$k/ $i; done; done
for in $(grep -rl 'include <px4_config.h' src platforms boards); do sed -i 's/#include <px4_config.h/#include <px4_platform_common\/px4_config.h'/ $i; done

Transitional headers for submodules are added (px4_{defines,log,time}.h)
2019-10-30 11:48:47 +01:00
Daniel Agar 6f1f5e0325 clang-tidy: partially fix readability-redundant-declaration 2019-10-28 10:50:31 -04:00
Daniel Agar a7f330075a clang-tidy: enable hicpp-braces-around-statements and fix 2019-10-28 10:50:31 -04:00
Daniel Agar 4192414576 clang-tidy: partially fix cppcoreguidelines-pro-type-reinterpret-cast 2019-10-28 10:50:31 -04:00
Daniel Agar 279df3b1b8 clang-tidy: partially fix hicpp-use-equals-delete 2019-10-27 19:19:07 -04:00
Daniel Agar ae27dd60a6
Jenkins re-enable clang-tidy and update .clang-tidy
- device/Device: fix explicit constructor and uninitialized fields
 - systemcmds/motor_test: update NULL to nullptr
2019-10-27 17:19:11 -04:00
Beat Küng 25aded36ec WorkQueue: avoid potential semaphore counter overflow
This could happen in the following cases:
- IRQ/publisher rate is faster than the processing rate, and therefore
  WorkQueue::Add is called at a higher rate
- a long-running or stuck task that blocks the work queue a long time

Both cases are not expected to happen under 'normal' circumstances (if the
system runs as expected).
2019-10-16 18:29:26 +02:00
Matthias Grob e843090383 Replace a lot of memset with {} initializers 2019-10-15 10:01:03 -04:00
Daniel Agar 3c623af903 ekf2: move to WQ with uORB callback scheduling 2019-10-02 19:44:46 -04:00
Daniel Agar 26364d44c9
px4_work_queue: command line status output and shutdown empty queues
* adds a work_queue systemcmd that will bring a tree view of all active work queues and work items
 * WorkQueues now track attached WorkItems and will shutdown when the last WorkItem is detached
2019-10-02 12:23:17 -04:00
Kjkinney 3f9b3fb4da px4_log: publish all PX4_INFO messages as well (#12954) 2019-09-27 14:04:30 -04:00
Julian Oes 78d3986013 platforms: fix main function signature 2019-09-03 11:52:54 -05:00
Beat Küng d3fb610fde mixer_module: create MixingOutput library and use in fmu
This should be a pure refactoring, no functional change.
2019-08-31 10:05:00 -04:00
Beat Küng 43fdcd7876 px4_middleware: remove that header and move px4::init to px4_init.h
delete include:
for i in $(grep -rl 'px4_middleware.h' src platforms); do sed -i '/#include <px4_middleware.h/d' $i; done
2019-08-30 07:59:44 +02:00
Beat Küng f32abe8534 src/platforms: move remaining source files to platforms/common 2019-08-30 07:59:44 +02:00
Beat Küng f8e0441e7b src/platforms/common: move to platforms/common
Script to update include paths:
for i in $(grep -rl 'include <px4_work_queue' src platforms); do sed -i 's/#include <px4_work_queue/#include <px4_platform_common\/px4_work_queue/' $i; done
2019-08-30 07:59:44 +02:00