Commit Graph

1243 Commits

Author SHA1 Message Date
Jukka Laitinen aae0876d82 platforms/rpi: Clean away the removed hrt_elapsed_time_atomic
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-02-25 13:35:14 +01:00
Jukka Laitinen 77f71e61d2 Add a generic hrt driver userspace interface
This adds a nuttx userspace interface for hrt driver, communicating with
the actual px4 hrt driver via BOARDCTL IOCTLs

This is be used when running PX4 in NuttX protected or kernel builds

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-02-25 13:35:14 +01:00
Jukka Laitinen 9f049b4dca Inline ts_to_abstime and abstime_to_ts
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-02-25 13:35:14 +01:00
Jukka Laitinen caaa13ddc0 uORB performance updates
Move some logic from Subscriber into uORBManager. This reduces calls from the
modules to the uORB manager, improving performance in protected build.

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-02-24 11:50:05 -05:00
Charles Cross f31f3370ef
Add support for Timer15 on H743 boards (#19228)
* Adds Timer15 to stm32_common, if the timer base is defined
* Adds Timer15 logic for DMA and AltFunc config on stm32h7 boards
* Adds TIM15 BDTR->MOE support in stm32_common timer init
* Adds support for TIM15 pwm channels on Matek H743 Slim
2022-02-21 16:52:38 -05:00
David Sidrane c0facec889 cdc_acm_check:Prevent USB disconect on param save
If the hardware support RESET lockout that has nArmed ANDed with VBUS
   vbus_sense may drop during a param save which uses
   BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE to prevent external resets
   while writing the params.  If we are not armed and nARMRED is low
   we are in such a lock out so ignore changes on VBUS_SENSE during this
   time.
2022-02-21 10:56:41 +01:00
Jukka Laitinen dab7b007de Auto-generate a list of kernel-side built-in modules(drivers)
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-02-18 07:58:58 +01:00
Jukka Laitinen 6071b87afc platforms/common/uORB: Separate IOCTLs going through boardctl interface from the original ones
It was a mistake to mix these two together, it is simpler to implement the boardctl interface
for the protected build, if the boardctl ioctls are different

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-02-18 07:53:13 +01:00
Jukka Laitinen f0d9f44f45 Add an ioctl handler to launch built-in modules in kernel side
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-02-18 07:53:13 +01:00
Jukka Laitinen db3baf6c26 Add an ioctl interface for userspace to kernel calls
This adds an ioctl interface for NuttX protected build, allowing
system calls from user space to kernel for uORB, HRT and crypto

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-02-18 07:53:13 +01:00
David Sidrane 3593cf795d NuttX With DMA/FLASH Backports 2022-02-16 10:09:02 -05:00
David Sidrane d05d7f4154 bl:Clean up formatting 2022-02-16 10:09:02 -05:00
David Sidrane 92590155fc px4_fmu-v6x:Bootloader move to TELEM1 with DMA 2022-02-16 10:09:02 -05:00
Jukka Laitinen 36d440f895 Add IOCTL interface to uORBManager for nuttx protected/kernel build split
When building uORB for NuttX flat build, or for some other target, everything
works as before.

When building uORB for NuttX protected or kernel build, this does the following:
- The kernel side uORB library reigsters a boardctl handler for calls from userspace
  and services the boardctl_ioctls by calling the actual uORB functions
- For user mode binaries, the uORBManager acts as a proxy, making boardctl_ioctl calls to the
  kernel side

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-02-14 09:10:49 +01:00
Beat Küng b6607a7b78 battery_status: do not publish if no voltage channel is defined
This is the case for boards with digital readout, like v5x, but still
enable the battery_status module for external analog driver options.

An alternative would be to not run battery_status depending on config.
2022-02-09 16:54:45 -05:00
David Sidrane 0c936e4fd2 serial_passthru:Move CONFIG_xxx to serial_passthru 2022-02-09 13:11:52 -05:00
Daniel Agar be3da5089c uORB: uORBDeviceNode use px4_cache_aligned_alloc 2022-02-08 10:20:50 -05:00
Peter van der Perk 9f97793491 Generate C/C++ header to expose px4board kconfig symbols to the preprocessor 2022-02-02 13:23:21 -05:00
David Sidrane 3fecf8a23c Added ability to launch passthru on u-center traffic 2022-02-01 21:49:29 -05:00
David Sidrane 2761112466 NuttX with CDCACM/OTGID backports
disable otg id
   cdcacm:support c_cflag in the termios structure
   and speed
2022-02-01 21:49:29 -05:00
David Sidrane cb06f82f0f gnss-m9n-f4:Board support clean up
SD is on SPI3 - correct pin mapping
   Fix DMA Mapping for all SPI and RX DMA on U[S]ART RX
   Fix Memory MAP SRAM size
   Removed unused GPIO
   Used proper I2C definitions
   Ensure Watchdog is configured for debugging
   Fixed FLASH param definitions
   Removed unedded SPI init

matek_gnss-m9n-f4:Correct Board ID and Size

Build order SJF

Added Support for F40x
2022-02-01 21:49:29 -05:00
Jukka Laitinen 70872d94c8 Split px4_layer into kernel and userspace parts for nuttx protected build
Split the px4_layer into user and kernel space libraries. Add some stubs for
user-space (e.g. version) where an interface to the kernel needs to be added

Use posix-versions for cpuload.cpp and print_load.cpp for userspace; these link to nuttx internals. This functinality could be built on top of posix (e.g. procfs) interfaces

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-01-31 20:26:08 -05:00
Jukka Laitinen 3a6ebe5fc1 NuttX Cmake changes to build combined kernel+userspace image in nuttx protected build
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-01-31 20:26:08 -05:00
Jukka Laitinen 70704ff9d6 platforms/nuttx/src/px4/common/CMakeLists.txt: Link px4_layer to nuttx_mm for gran allocators
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-01-27 12:42:40 -05:00
Jukka Laitinen 4c75f1d505 platforms/nuttx/CMakeLists.txt: fixes to accommodate other linker changes
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-01-27 12:42:40 -05:00
Jukka Laitinen 705171eb53 Fix linking for posix targets
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-01-27 12:42:40 -05:00
Jukka Laitinen e959fcf9d1 bootloader: link stm bootloaders to nuttx_arch for flash functions
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-01-27 12:42:40 -05:00
Jukka Laitinen fe5059b0e8 s32k1xx/led_pwm: link to arch_io_pins
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-01-27 12:42:40 -05:00
Jukka Laitinen 68729e8ec0 nuttx/rpi io_pins: link to drivers_board for timer_io_channels dependency
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-01-27 12:42:40 -05:00
Jukka Laitinen d181fe0cee nuttx/stm io_pins: link to drivers_board for timer_io_channels dependency
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-01-27 12:42:40 -05:00
Jukka Laitinen 76d4b6c7d0 arch_board_reset: link to nuttx_arch / nuttx_karch for up_systemreset dependency
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-01-27 12:42:40 -05:00
Jukka Laitinen 7bb33e65ae Remove px4_work_queue linking to px4_platform
Remove linking to px4_plaform in here; this breaks linking for nuttx protected build

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-01-27 12:42:40 -05:00
Jukka Laitinen 98906c224b Don't link px4_platform directly to uORB
Since uORB is split into kernel and userspace parts, it is no longer possible to just
link uORB into px4_platform, which is used in both kernel and user side.

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-01-27 12:42:40 -05:00
Jukka Laitinen 54f1e12684 Link arch_spi with drivers_board
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-01-27 12:42:40 -05:00
Jukka Laitinen ff4eae2c9b Fix px4_impl_os for protected build
For NuttX protected or kernel build, the prebuilds can't contain libraries which are
different for kernel and user-space in protected/kerenl builds

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-01-27 12:42:40 -05:00
Jukka Laitinen d94cc1e114 Add kernel/userspace and nuttx_syscall libraries to build
Build NuttX proxies, stubs and separate user space and kernel space libraries

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-01-27 12:42:40 -05:00
Beat Küng 92769bd2b2 dshot: remove BOARD_DSHOT_MOTOR_ASSIGNMENT & handle timer channel gaps 2022-01-21 20:41:15 -05:00
David Sidrane a11fe60135 imxrt:ADC extend timeout 2022-01-21 13:07:44 -05:00
Beat Küng bcd057ac3e uORB: fix copy-paste mistake in orb_print_message_internal
Could have led to invalid memory access.
2022-01-20 12:58:20 -05:00
Daniel Agar 446729566d platforms/nuttx: px4io_serial always cleanup DMA before next bus exchange
- this really shouldn't be necessary, but worst case it's harmless and
much better than potentially falling out of the sky
2022-01-19 18:00:18 -05:00
Daniel Agar 8067207ea6 px4_work_queue: rename serial port WQs 2022-01-18 14:56:15 -05:00
Julian Oes be9385ef06 cmake: use at least 1 core to build SITL
If we use -j 0, ninja fails with invalid argument.
2022-01-17 17:07:31 -05:00
Beat Küng cd2bb14f9b stm32h7/micro_hal.h: add RCC_APB1ENR_TIM4EN 2022-01-17 10:41:33 -05:00
Julian Oes 9eda5b373c posix: add fuzz testing using MAVLink messages
This adds the env option PX4_FUZZ which runs the LLVM libFuzzer which
throws random bytes at mavlink_receiver using MAVLink messages over UDP.

The MAVLink messages that are being sent are valid, so the CRC is
calculated but the payload and msgid, etc. are generally garbage, unless
the fuzzing gets a msgid right by chance.

As I understand it, libFuzzer watches the test coverage and will try to
execute as much of the code as possible.
2022-01-07 10:17:12 -05:00
David Sidrane eac92ec671 imxrt:ADC fix timeouts 2022-01-03 06:02:19 -08:00
Daniel Agar f76aa0e772 cmake: NuttX ARMV7M_STACKCHECK skip ekf2
- px4_fmu-v5_stackcheck switch from icm20689 -> bmi055 (lower rate)
 - this is to make performance tolerable
2022-01-01 18:43:27 -05:00
Daniel Agar 03371f8522 NuttX with bch flush backport 2021-12-31 10:59:56 -08:00
Daniel Agar 6d0339ba0c I2CSPIDriverBase: sensor start failure ERROR if internal, WARN if external 2021-12-28 11:05:35 -05:00
Daniel Agar d94767ef88 cmake: NuttX use cygwin friendly path for linker script 2021-12-27 12:19:12 -05:00
Beat Küng fe1b726b62 ScheduledWorkItem: do not call ScheduleClear() if not init in destructor
This avoids that unit tests trying to access a wq hang.
It still fails with an error currently.
2021-12-24 20:06:13 -05:00
Beat Küng 590239dedb work_queue: increase rate_ctrl stack size by 150 B
WARN  [load_mon] wq:rate_ctrl low on stack! (172 bytes left)
2021-12-24 20:06:13 -05:00
Daniel Agar 38731662c6 parameters use bitset for mark_unsaved 2021-12-24 14:32:40 -05:00
PX4 BuildBot a069a47d50 Update submodule nuttx to latest Thu Dec 23 18:11:37 UTC 2021
- nuttx in PX4/Firmware (d0ce570535): d4c06e9dfb
    - nuttx current upstream: 378032a44b
    - Changes: d4c06e9dfb...378032a44b

    378032a44b 2021-12-15 David Sidrane - [BACKPORT] stm32f7:sdmmc invalidate before DMA to avoid eviction overwrite
2021-12-23 14:50:47 -05:00
Daniel Agar a4040f7afd px4io_serial: always perform full abort DMA on error
- enable DMA error perf count
2021-12-23 12:48:42 -05:00
Beat Küng e29759d877 WorkQueueManager: explicitly convert PTHREAD_STACK_MIN to int
fixes a compiler error on GCC 11.2.1:
error: no matching function for call to ‘max(long int, int)’
2021-12-22 08:47:33 -05:00
Igor Mišić 298a8c4637 boards/fmu-v5x: allocating PPS pin
- start pps_capture before pwm_out
2021-12-17 07:56:08 +01:00
Igor Mišić 60a212f717 px4_arch: add PX4_MAKE_GPIO_EXTI 2021-12-17 07:56:08 +01:00
Jukka Laitinen ce6147f570 uORB: Remove transfer of memory allocation ownership to CDev
- Allocate and free the node name in uORBDeviceNode.
- Add protected build support by de-allocating the name with kmm_free, when
  running in kernel side. strdup allocates from the kernel heap in NuttX kernel
  space.
- Remove the CDev::unregister_driver_and_memory(), it is no longer used

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-12-13 22:52:36 -05:00
Jukka Laitinen 77af102cab px4_work_queue: Use px4_task_spawn_cmd for WorkQueueRunner in NuttX protected
In NuttX protected build there are separate work queues in kernel and user sides.

pthreads are only available in user side, so use tasks and kthreads for
memory protected builds.

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-12-09 20:42:28 -05:00
Jukka Laitinen 3aab4d2daf px4_task_spawn_cmd: launch kernel thread in protected/kernel build on kernel side
Also task name is accessible only in kernel side for protected/kernel build

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-12-09 20:42:28 -05:00
Jukka Laitinen d0d7f29422 platforms/common/shutdown.cpp: Enable boardctl functions for shutdown and poweroff
Shutdown and poweroff must go through boardctl in NuttX protected build

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-12-07 09:24:53 -05:00
Daniel Agar 9db5bc0755 px4_mtd: increase retries, wait inbetween, try decreasing frequency 2021-12-06 09:37:08 -05:00
Daniel Agar f63a7642d6 NuttX debug helper improvements
- use NuttX gdb script for nxthreads and thread backtrace
 - update jlink_gdb_backtrace and jlink_debug_gdb helper targets to use
NuttX gdb script
 - Debug/PX4 fix "perf" divide by zero
 - Debug/PX4 add "dmesg"
2021-12-05 19:18:56 -05:00
Beat Küng cbd6e735ad fix console_buffer: avoid potential deadlock when using dmesg over MAVLink shell
dmesg was locking the console buffer, then writing to stdout (a pipe in
the case of the MAVLink shell).
This might block, waiting for mavlink to read from the pipe. If however
mavlink tries to write to the console at that time, the lock is already
taken.
This patch avoids nested locking by using a separate buffer.
2021-11-30 08:49:52 -05:00
Daniel Agar bc7001ba49 NuttX apps with [REJECTED] mkfatfs DMA memory change 2021-11-29 21:49:35 -05:00
Jukka Laitinen 929820136a Move sw_crypto and stub_keystore under src/drivers
This is more logical place for the "backend" implementation than
directly under platform.

This also allows making other implementations as "real" drivers, as well as proper configuration via Kconfigs

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-11-29 11:09:51 -05:00
David Sidrane 7393a68e28 NuttX with ramtron and BCH backports 2021-11-26 19:27:29 -05:00
Daniel Agar 51da169ccb cmake: nuttx apps build depend .c and .h files 2021-11-25 17:24:23 -05:00
Daniel Agar 7d985ec7c5 NuttX with Backports for SD fixes 2021-11-25 13:11:45 -05:00
David Sidrane 3cf901b29c NuttX Apps with backport CONFIG_MKFATFS_BUFFER_ALIGMENT 2021-11-24 09:46:23 -05:00
Jukka Laitinen b66270f8a8 Inline uORBDeviceNode::copy for performance improvement
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-11-24 09:11:45 +01:00
Jukka Laitinen 3f884c5d24 Inline deviceNodeExists and getDeviceNode in uORB DeviceMaster
This gives a small performance improvement

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-11-24 09:11:45 +01:00
Jukka Laitinen bb307cd462 Fix comparing orb_metadata in uORB::DeviceNode::publish
Don't compare pointers to metadata, but the metadata contents.

In protected/kernel build there are two sets of metadata, on on kernel
side and another in user side. Thus the comparison of pointers would just
always fail. Compare orb_id instead

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-11-24 09:11:45 +01:00
Jukka Laitinen 0b9505453d Clean up interfaces towards uORB
Proxy all calls to the DeviceNode through Manager;
- This hides the DeviceNode from publishers and subscribers
- Manager can be made an interface class between user and kernel spaces in protected build
- This doesn't increase code size or harm the performance on flat build

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-11-24 09:11:45 +01:00
Beat Küng bcba3dfe52 control_allocator,angular_velocity_controller: run on rate_ctrl wq 2021-11-23 12:40:22 -05:00
Daniel Agar 3140bf167c
NuttX submodule update with work_usrthread.c fixes 2021-11-22 17:41:49 -05:00
Daniel Agar 7653bd1757 cmake fix NuttX config import for 0 values 2021-11-21 12:33:29 -05:00
Jani Paalijarvi 02336acd61 Improve SPI bus implementation
Make possible to define chip-select pin for internal SPI.
By defining chip-select pin, it's possible to start specific SPI device only.
This allows to have several same type of sensors on the same bus with different orientation.
2021-11-19 07:47:18 +01:00
Daniel Agar f5d9b01f5c
NuttX build in place
- cmake NuttX build wrapper compile in place instead of copying source tree to build directory
    - slightly faster skipping necessary copying (depending on system)
    - allows debugging in place
    - easier to work directly in NuttX following official documentation
    - simplifies overall build which should make it easier to resolve any remaining NuttX dependency issues in the build system
 - the downside is switching back and forth between different builds always require rebuilding NuttX, but I think this is worth the improved developer experience
 - also no longer builds px4io and bootloader in every single build, for most users these rarely change and we're wasting a lot of build time
2021-11-15 18:47:38 -05:00
Daniel Agar 7b7b7acd36 i2c_spi_buses: respect CONFIG_I2C and CONFIG_SPI
- bmp280, dps310, and ms5611 barometers support boards without I2C
2021-11-15 15:57:33 -05:00
Jukka Laitinen 356de6ccf1 Factor cdc_acm_init away from px4_init
In protected build, this needs to go to user-space initialization as it
calls apps (sercon) and launches mavlink.

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-11-09 21:28:28 -05:00
Jukka Laitinen 39c0c68167 print_load: Remove reference to CONFIG_MAX_TASKS
This is already removed from nuttx, and in posix the size of s->last_times
can be just checked with sizeof()

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-11-09 21:25:10 -05:00
Jukka Laitinen 9299a5c3f6 hrt: Add interface functions for latency counters
Add interface functions for fetching latency buckets and counters and use
those in perf_counter.cpp. This cleans up the usage of perf counters, when variables defined in hrt_drv are not referenced directly from perf.

This also enables implementing kernel-userspace interface for those for
nuttx protected/kernel build.

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-11-09 21:24:25 -05:00
Guilherme Lawless 47a191489e
cmake: sitl_gazebo build use memory information from the system to estimate the parallel jobs
Using cmake_host_system_information, grabs AVAILABLE_PHYSICAL_MEMORY and adds another job for every 1.5GB of available memory.

This is tested on a single system with 16 logical cores and 16GB RAM (~11.5GB available, reported correctly by cmake).
2021-11-07 15:37:48 -05:00
David Sidrane 96101a9c11 NuttX backports of imxrt dcache fixes to support WB & USB 2021-11-05 13:50:02 -04:00
David Sidrane e2b4e435a9 Build system:Board level control of no-unaligned-access 2021-11-05 13:50:02 -04:00
David Sidrane af9f8f08c6 NuttX PX4 build - capture log in VERBOSE=True|1 2021-11-05 13:50:02 -04:00
Daniel Agar 9c15be22d6 mc_autotune_attitude_control: add new MC_AT_EN parameter to enable
- only enabled by default on boards that aren't memory constrained
2021-11-05 09:52:07 -04:00
Vatsal Asitkumar Joshi ea1ae73526
Support for Raspberry PI RP2040 MCU (#18083) 2021-11-03 12:14:30 -04:00
David Sidrane 38e2e6a01f
Use NuttX MPU Reset (#18283)
* NuttX with MPU reset backports

* Use NuttX MPU reset
2021-10-25 18:05:31 -04:00
Landon Haugh 24cd0c6fa3 Enablement of PX4 SPI driver for UCANS32K146 2021-10-25 08:36:54 -07:00
Daniel Agar 17328bef69 Jenkins attach GDB and print back trace on failure 2021-10-21 14:04:33 -04:00
Beat Küng c0f75b1c79
dshot: add missing '#pragma GCC diagnostic push' 2021-10-20 08:11:07 +02:00
Beat Küng 8a2b310b83 topic_listener: avoid code generation, use existing metadata at runtime
This reduces flash size for v5 by ~110KB, the topic listener now only adds
about 1.2KB.
2021-10-20 08:10:05 +02:00
Beat Küng 4c73ac3805 uorb: use single byte for internal types in o_fields metadata
Reduces flash usage by ~9KB.
2021-10-20 08:10:05 +02:00
mcsauder 21163d859e Whitespace cleanup. 2021-10-19 13:29:26 -04:00
Beat Küng da1df5352c fix pwm: only update oneshot timers owned by the current pwm_out instance
This fixes the case where oneshot was enabled with multi-instance pwm_out,
triggering oneshot updates too close to each other and as a result could
lead to spinning motors while disarmed.
2021-10-18 18:45:19 -04:00
Beat Küng d9bf03b2dc holybro/durandal-v1: add capture pins to list of pwm pins 2021-10-18 18:45:19 -04:00
Beat Küng 0ab4a24de8 px4/fmu-v5: add capture pins to list of pwm pins 2021-10-18 18:45:19 -04:00
Beat Küng 15daded6b0 refactor output_limit: split output_limit_calc_single into separate function 2021-10-18 18:45:19 -04:00
AuroraRAS 62dd38fe35 Prepare for Android NDK build
Modify CMakeList.txt prepare for Android NDK build

Signed-off-by: AuroraRAS <chplee@gmail.com>
2021-10-18 14:55:56 -04:00
Daniel Agar 7de00469a6
platforms: nuttx px4_init fix USB serial mavlink autodetect 2021-10-13 16:34:45 -04:00
Jaeyoung-Lim e2f048f608 Add sitl glider model
Add airframe configs for SITL glider model

This commit adds an airframe config for a glider model
2021-10-10 12:33:25 -04:00
bresch 21b1f090e6 SITL: add typhoon_h480_ctrlalloc target 2021-10-08 09:35:40 +02:00
Peter van der Perk bfa87fdac7 Kconfig fix wrong nuttx submodule commit 2021-10-07 10:09:01 -04:00
Peter van der Perk 60790f7112 Backport boards: modalai_fc-v1 update default.cmake (#18202) 2021-10-07 10:09:01 -04:00
Daniel Agar beb358a344 px4_work_queue: adjust status formatting to accommodate longer names (eg mc_autotune_attitude_control) 2021-10-05 18:09:00 -04:00
Daniel Agar 896ad3a627
cmake: fix find_program ozone 2021-10-04 18:27:50 -04:00
Daniel Agar 6d78054f50
mavlink USB auto start/stop on boards with VBUS
- no longer start sercon or mavlink usb by default
 - on USB connection (VBUS) monitor serial USB at low rate and start Mavlink if there's a HEARTBEAT or nshterm on 3 consecutive carriage returns
 - the mavlink USB instance is automatically stopped and serdis executed if USB is disconnected
 - skipping Mavlink USB (and sercon) saves a considerable amount of memory on older boards
2021-10-03 15:32:54 -04:00
bresch 5874b1f87c mc atune: add module to all targets
- adjust flash constrianed targets to fit
2021-10-02 18:12:05 -04:00
David Sidrane 7c9903f610 stm32h7:px4io_serial use TRBUFF
- includes NuttX with TRBUFF backports
2021-09-29 23:55:00 -04:00
David Sidrane f56701e72f micro_hal:Remove px4_savepanic on arch without hardfault logging 2021-09-29 23:51:25 -04:00
David Sidrane cb47203a9e NuttX with deglitched GPIO backports 2021-09-29 23:50:11 -04:00
David Sidrane 2abbf791b3 NuttX with deglitched GPIO backports 2021-09-29 14:37:17 -04:00
Peter van der Perk 360c3781f3 UCANS32K146-01 Add CAN tranceiver self test 2021-09-29 09:36:14 -07:00
Jukka Laitinen 3db76d88fe Add crypto key generation functions
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-09-27 17:45:07 +02:00
Jukka Laitinen 4c6779812d Add keystore_put_key interface function for storing keys permanently
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-09-27 17:45:07 +02:00
Jukka Laitinen fc2668cba1 Add encryption function for the crypto_backend and px4_crypto
Take into use libtomcrypt library to add RSA and some other algorithms
for SW ecnryption use case

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-09-27 17:45:07 +02:00
Jukka Laitinen be4f7cabf9 Add compilation of nuttx_crypto
NuttX has lots of usable functionality for crypto, such as rng with entropy pool

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-09-27 17:45:07 +02:00
Jukka Laitinen d36a91ceaf Add generic px4 interface for crypto features
Add common functions, implemented for nuttx, and link to architecture specific libraries

Make a separate library to wrap nuttx random number generator as "os_random".

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-09-27 17:45:07 +02:00
Jukka Laitinen aa61bc4942 Add functions for initializing empty crypto backend handles
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-09-27 17:45:07 +02:00
Daniel Agar 9a3fa6199b uorb top report total publication rate 2021-09-26 12:29:11 -04:00
Daniel Agar 089c962d92 px4io: moving mixing to FMU side
Using mixers on the IO side had a remote benefit of being able to
override all control surfaces with a radio remote on a fixed wing.
This ended up not being used that much and since the original design
10 years ago (2011) we have been able to convince ourselves that the
overall system stability is at a level where this marginal benefit,
which is not present on multicopters, is not worth the hazzle.

Co-authored-by: Beat Küng <beat-kueng@gmx.net>
Co-authored-by: Daniel Agar <daniel@agar.ca>
2021-09-25 19:15:05 -04:00
Beat Küng e73172b537 hrt: remove hrt_elapsed_time_atomic
There's no protection on posix
2021-09-23 09:23:08 +02:00
Beat Küng 810d2e9497 ModuleParams: remove parent in destructor
This allows for dynamic deletion of children objects (in most cases this
is not used).

Uses ~100B memory.
2021-09-11 15:07:49 -04:00
Jukka Laitinen 28dbd8dc1d NuttX at 10.1.0+
NuttX backport fixing ARM protected build
2021-09-09 04:43:22 -07:00
Beat Küng c5c80e31b6 boards: remove DIRECT_INPUT_TIMER_CHANNELS from board_config.h 2021-09-08 16:10:24 -04:00
Beat Küng 062dd28f4d camera_capture: use up_input_capture_set directly
It reserves the channel and pwm_out will not use it
2021-09-08 16:10:24 -04:00
Beat Küng 78b5cdae4c s32k1xx: io_timer: reserve pins & timers on first use 2021-09-08 16:10:24 -04:00
Beat Küng ab828b8e94 kinetis: io_timer: reserve pins & timers on first use 2021-09-08 16:10:24 -04:00
Beat Küng 7d9a3bf29f imxrt: io_timer: reserve pins & timers on first use 2021-09-08 16:10:24 -04:00
Beat Küng 9a74c6f3c6 stm32: io_timer: lock around io_timer_allocate_channel and io_timer_get_channel_mode
This is to avoid potential race conditions during startup.
All startup code runs sequentially atm, so this is just for robustness
for later (e.g. concurrent pwm_out and dshot start).
2021-09-08 16:10:24 -04:00
Beat Küng 847bd120fa io_timer: reserve pins & timers on first use
This allows modules to do a first-come-first-serve pin/timer reservation
on bootup.
E.g. camera trigger reserves any of the pins, and then PWM/DShot output
will just use the rest of the available pins.
2021-09-08 16:10:24 -04:00
Daniel Agar 000765e9f0 NuttX mount procfs and binfs in px4 init 2021-09-08 10:21:24 -04:00
Daniel Agar 65b1a9648d Tools/HIL/run_nsh_cmd.py: fail if ERROR printed in output 2021-09-01 15:16:00 -04:00
Daniel Agar 5dfc07cb1b systemcmds/param: add set-default sient (-s) option 2021-09-01 15:16:00 -04:00
Daniel Agar 6be7926ed3 px4io: add watchdog
- F1 iwdg:Support optional configuable init

Co-authored-by: David Sidrane <David.Sidrane@NscDg.com>
2021-09-01 15:16:00 -04:00
Daniel Agar 7925787f62 px4io_serial: ensure TX DMA is stopped if exiting early on stream error
- otherwise the next retry can happen quickly enough that dma setup
hangs waiting for the stream
2021-08-31 23:11:07 +02:00
Jukka Laitinen c3c30e5d4f Fix memory corruption when work queue is being deleted
When the last WorkItem is deleted, it is removed from a work queue and the
queue is being stopped. But, the queue itself might get deleted in the middle,
in a higher priority thread than where the WorkItem deletion was performed from

If the WorkQueue::Detach accesses the member variables after this, there is memory
corruption

This happens in particular when launching i2c or spi devices in
I2CSPIDriverBase::module_start:

- The "initializer" is deleted when the instance is not found and the iterator
  while loop continues.
- The workqueue is deleted in the middle of "initializer" deletion when the
  WorkQueueRunner returns.

This prevents deletion of the WorkQueue before the Detach has been finished,
in the specific case that the ::Detach triggers the deletion

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-08-27 10:43:45 +02:00
Jukka Laitinen 523578d2ce Increase stack size of wq:manager and worker threads for 64 bit targets
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-08-24 10:16:27 -04:00
David Sidrane 78b76cb636 i2c_spi_buses:Support devices that may change address 2021-08-20 10:15:57 -04:00
Daniel Agar 8a8171c7aa platforms/nuttx: px4_init initialize and reset all I2C buses 2021-08-17 09:54:50 -04:00
Daniel Agar 2b581ef407 platforms/nuttx: s32k14x & s32k1xx add i2c_hw_description.h 2021-08-17 09:54:50 -04:00
Beat Küng f00f3d1a27 dshot: improve performance by removing extra motor_buffer array
Reduces CPU load by almost 1.5% @ 2khz on F4 and F7.

This changes the motor ordering on boards where the timer ordering does
not match the order of the timer usage in the channels defintion.
Only omnibus f4sd is affected.
2021-08-16 11:05:39 -04:00
Beat Küng afed10618b dshot: inline up_dshot_motor_data_set and up_dshot_motor_command
Slight performance improvement (~0.1% @1khz on F4)
2021-08-16 11:05:39 -04:00
David Sidrane 518700b39b platforms/nuttx/CMakeLists:Resolve fs->libc(strcat) libc->fs 2021-08-13 14:22:00 -04:00
David Sidrane bb913ae11a system_load:Track Dynamic PID hash 2021-08-13 14:22:00 -04:00
David Sidrane 58fc5b21b8 NuttX at 10.1.0+
With PX4 contrib for building
2021-08-13 14:22:00 -04:00
David Sidrane 173e5c7554 NuttX:Track Stack naming changes 2021-08-13 14:22:00 -04:00
David Sidrane 4353d0faf3 print_load:Support NuttX Dynamic FDs 2021-08-13 14:22:00 -04:00
David Sidrane ec61512cdf NuttX inits null console 2021-08-13 14:22:00 -04:00
David Sidrane 01ef9cf3e6 NuttX at 10.1.0+
With PX4 contrib for building
2021-08-13 14:22:00 -04:00
Beat Küng f88f224fe6 logger: avoid data bursts by distributing slow subscription updates over time
There's an increasing amount of slow logged topics at 1-2Hz, which were all
updated in the same logger iteration, leading to data bursts. For log
streaming this started to exceed uart buffer sizes. By distributing updates
more equal over time those bursts are removed, reducing buffer size
requirements.

Tests showed during steady state a reduction of maximum topic updates per
iteration from 40 down to 17.
Also the SD log buffer fill level is more constant.
2021-08-12 10:09:11 -04:00
Daniel Agar e900f2ea54 boards: Advanced Technology Labs (ATL) Mantis EDU support and airfarme (SYS_AUTOSTART 4061)
Co-authored-by: Julian Oes <julian@oes.ch>
Co-authored-by: Daniel Agar <daniel@agar.ca>
2021-08-04 17:15:24 -04:00
David Sidrane ced366b74e Add Option NO_HELP for CONSTRAINED_FLASH system 2021-07-30 22:35:02 -04:00
Daniel Agar fe1eb8cd62 cmake cleanup jlink flashing helpers 2021-07-23 15:07:25 -04:00
David Sidrane 0709a9bb1c NuttX With Kinetis LPUART DMA backport 2021-07-20 18:22:35 -04:00
David Sidrane b85a01f4c2 NuttX with Kinetis SerialPoll back in 2021-07-20 07:52:10 -07:00
JaeyoungLim 58060b23d9
Add ignition gazebo support for PX4 Software-In-The-Loop simulations
This commit adds SITL support for ignition gazebo. Ignition gazebo is a replacement for the "classic" gazebo for future applications.

The simulation can be run as the following
```
make px4_sitl ignition
```
2021-07-19 19:59:41 -04:00
Daniel Agar d79eea0c41
Jenkins: HIL flash bootloaders
- add new jlink_upload_bootloader helper target
2021-07-18 23:33:00 -04:00
Daniel Agar 774ad80ba0 systemcmds/tests: split out microbenchmarks and remove obsolete tests
- reorganize Jenkins HIL tests
2021-07-18 18:02:33 -04:00
Daniel Agar 65745a3676 purge broken qurt support and atlflight boards 2021-07-16 08:53:36 -04:00
Daniel Agar 4a0fa08953 Tools/HIL/run_nsh_cmd.py fail if command failed 2021-07-15 23:29:46 -04:00
Daniel Agar fcf0d3536f
NuttX debug jlink scripts minor improvements
- script return non-zero exit if there's a failure
 - upload script look for both gdb-multiarch and arm-none-eabi-gdb
2021-07-15 17:07:51 -04:00
Jaeyoung-Lim db1dc1c9a1 Add airframe configuration and make target for believer
This commit adds an airframe configuration and make target for believer
2021-07-13 18:04:52 +02:00
Daniel Agar d8704cee67 platforms: px4 log build string then print (fputs) 2021-07-10 13:14:49 -04:00
David Sidrane f5e5794930 platforms/common:SPI - fix hang on bords supporting BOARD_HAS_BUS_MANIFEST 2021-07-10 11:37:29 +02:00
TSC21 e39e3b3418 events interface: chance uORB 'sequence' to 'event_sequence'
The reason is that sequence is an IDL reserved keyword, which results on failure when parsing with FastRTPSGen.
2021-07-09 13:24:13 +02:00
Beat Küng c5aef9d512 i2c_spi_buses: add support for multiple instances of the same device on a bus
This also simplifies the API a bit, since we anyway have to change the
drivers to pass additional information (the bus device index).

The orientation flag is merged with the rotation.
2021-07-08 12:59:35 -04:00
Daniel Agar e4983ab88c
px4_platform_common: atomic support larger types with critical sections (on NuttX) 2021-07-08 10:56:25 -04:00
Beat Küng 38f3b8d356 mavlink & system: add events interface
- sending protocol
- uorb event message & template methods for argument packing
- libevents submodule to send common events and handle json files
- cmake maintains a list of all (PX4) source files for the current build
  (PX4 modules + libs), which is used to extract event metadata and
  generate a json file
2021-07-07 21:38:09 -04:00
Daniel Agar 6dd0a58302 [at24c] free perf counter if px4_at24c_initialize fails
- add driver prefix to perf counter naming
2021-07-05 21:22:08 -04:00
David Sidrane 9dee09b81b NuttX and Apps updated w/ALL backports 2021-07-02 09:08:10 -07:00
David Sidrane 5ea4b7dc9e NuttX with Kinetis eDMA (SPI, Serial) Backports 2021-07-02 09:08:10 -07:00
Beat Küng 9b7170551c ModuleBase: allow configurable timeout for wait_until_running() 2021-07-02 12:45:18 +02:00
David Sidrane 3e00450052 NuttX with SDMMC BACKPORT 2021-07-01 11:51:14 -07:00
Jukka Laitinen d83033f449 Take the crypto_backend library into use in bootloader for signature verification
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-06-25 08:35:58 +02:00
Jukka Laitinen 0d4f481035 Add simple SW implementations for crypto_backend and keystore_backend
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-06-25 08:35:58 +02:00
Jukka Laitinen d068ae48d6 Add header file for arhitecture/implementation specific px4 crypto and
configuration for cmake

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-06-25 08:35:58 +02:00
TSC21 145e7387fb posix: start the microRTPS client in sim every time the module is available 2021-06-21 16:36:44 +02:00
Daniel Agar 500c45e798 uORB: Subscription check if uORB::Manager instance is valid
- this is necessary if uORB::Subscription is used with static storage
duration
2021-06-17 08:07:24 +02:00
David Sidrane 9377b02c58 Track NuttX Timer changes 2021-06-16 17:07:47 +02:00
David Sidrane 05bdef867d Track NuttX syslog change 2021-06-16 17:07:47 +02:00
David Sidrane f3624c172c kinetis pinirq:Use inttypes 2021-06-16 17:07:47 +02:00
David Sidrane 6e5a86b6fe dshot:Matched signature to drv_pwm_output.h 2021-06-16 17:07:47 +02:00
David Sidrane dc23c85085 px4/common:mtd Use inttypes 2021-06-16 17:07:47 +02:00
David Sidrane 84dd8839a2 i2c_spi_buses:Track NuttX change to getopts avoid name collision
NuttX #defined optarg and getopt to move to TLS. This fixes the
  name collision.
2021-06-16 17:07:47 +02:00
AlexKlimaj dddd2c3297
drivers/distance_sensor: New Broadcom AFBR-S50LV85D distance sensor driver
* Basic Broadcom AFBR-S50 driver using vendor API and binary blob https://github.com/Broadcom/AFBR-S50-API
* fix ARK Flow paw3902 rotation
2021-06-15 12:12:24 -04:00
David Sidrane 9c8e95db8d NuttX w/NXP contrib for FlexCAN fixes 2021-06-12 06:22:01 -07:00
echoG 6bc09138c1
Adding BatMon smart battery as a module and refactoring SMBUS based SBS 1.1 spec to a library 2021-06-09 12:17:45 -04:00
Daniel Agar 47b9016f5e I2CSPIDriverBase: print rotation and i2c address if set 2021-06-08 09:27:21 +02:00
achim 66dbc1e25f Update rc.board_arch_defaults
logger doesn't start at all up to 4k buffer
2021-06-05 11:46:30 -04:00
achim fd2161b6bf Update rc.board_arch_defaults
logger doesn't start at all up to 4k buffer
2021-06-05 11:46:10 -04:00
achim 1ab7943940 Update rc.board_arch_defaults
Logger doesn´t start at all with 4k buffer
2021-06-05 11:45:53 -04:00
David Sidrane 32e92ba817 Revert:Pull downs - bad levels cause motor spins 2021-06-01 15:18:47 -04:00
Daniel Agar 806b462935 px4_work_queue: increase UART stack 2021-05-31 14:49:40 -04:00
Jukka Laitinen 34de392425 Add compiler cmake files for RISC-V (rv64gc) targets
This adds the basic support for riscv64-unknown-elf compiler amd rv64gc ISA

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-05-28 22:22:57 -04:00
Jukka Laitinen 935253357a nuttx compilation: Don't assume "arm" to enable risc-v compilation
Replace "arm" by "${CONFIG_ARCH}"

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-05-28 22:22:57 -04:00
Jukka Laitinen 675a5a2b2c bootloader: change flash_cache addresses to uintptr_t
To fix comilation errors on 64 bit platforms

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-05-26 12:57:37 -07:00
Jukka Laitinen 64d264b49a bootloader: Move chip specific things under chip specific folders
- move systick.c under chip specific sources
- move do_jump into chip specific main.c as arch_do_jump
- wrap flash writes to "arch_flash_write" and implement in chip specific main.c
- add bootloader TOC check
- sync image_toc.h with the version currently in use with old bootloader

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-05-26 12:57:37 -07:00
Daniel Agar c3884b5bc1
fake_imu (formally fake_gyro) updates for testing gyro filtering
- fake_imu now publishes sine sweeps over 10 seconds
 - accel is also published so that fake IMU can be selected when the only option
2021-05-17 20:26:25 -04:00
Peter van der Perk 60a083b662 canbootloader clear pending systick interrupts 2021-05-17 05:05:24 -07:00
Daniel Agar ecf2cd3afb
CAN node STM32F7 support and Freefly RTK GPS CAN node 2021-05-16 13:10:02 -04:00
Daniel Agar ad0482155e ROMFS: reduce LOGGER_BUF default to 8 kB on older boards 2021-05-12 17:06:33 +02:00
David Sidrane 69e0c2fc10 px4:platform support SPI configuration selection on HW REV 2021-05-10 09:11:50 +02:00
David Sidrane 541697d193 NuttX Backports Fixing SDIO/SDMMC Data Timeouts
stm32, F7 and H7
2021-05-08 04:40:54 -07:00
David Sidrane 8d82560308 NuttX Backports
[BACKPORT] binnfmt:Fix return before close ELF fd
   stm32h7: serial: use dma tx semaphore as resource holder
   [BACKPORT] stm32h7:Serial Add RX and TX DMA
   [BACKPORT] drivers/serial: fix Rx interrupt enable for cdcacm
   [BACKPORT] stm32h7:Allow for reuse of the OTG_ID GPIO
   [BACKPORT] stm32f7:Allow for reuse of the OTG_ID GPIO
2021-05-07 11:50:38 -07:00
David Sidrane 3d166d3279 PWM:Add Channel mask to up_pwm_servo_arm & up_pwm_servo_deinit 2021-05-05 20:48:06 +02:00
David Sidrane d5b60f7002 NuttX with WIP OTG_ID 2021-05-05 20:48:06 +02:00
David Sidrane 362db92515 Define PX4_MAKE_GPIO_INPUT_PULL_DOWN 2021-05-05 20:48:06 +02:00
David Sidrane dcbfc9de2d io_timer:Fixed imposible logic 2021-05-05 20:48:06 +02:00
Daniel Agar 3b7ce61901 px4_work_queue: increase wq:rate_ctrl stack slightly 2021-05-04 17:40:56 -04:00
David Sidrane cd2aceb363 stm32_common:board_reset Fix reboot -b broke by canbootloader 2021-05-03 05:21:25 -07:00
Beat Küng 0a98c5a7f4 Subscription: fix ChangeInstance 2021-04-27 10:29:09 -04:00
JacobCrabill cc81c7d49e poor-mans-profiler: Add documentation
Now sets the GDB serial device to the path of a DroneCode Probe by
default, with option command-line option override.

A few usage instructions added to the top of the file.
2021-04-26 08:47:49 +02:00
Daniel Agar f9d8c613b0 px4_work_queue: increase nav_and_controllers stack 2021-04-21 07:34:13 +02:00
David Sidrane 96d0755afd NuttX with SDMMC Backport 2021-04-09 15:53:26 -04:00
David Sidrane 5e73fe588e NuttX with SRAM4-heap-bp 2021-04-03 14:13:23 -04:00
Beat Küng e9370c658a
nuttx cmake: include upload.cmake if it exists (same as on posix) 2021-03-31 11:25:11 +02:00
Daniel Agar 7314b69adc cmake: fix jlink_flash_uavcan_bin helper 2021-03-28 12:39:22 -04:00
David Sidrane 7f2566dd8a
NuttX STM32H7 16 bit SPI fixes + ADIS16470 updates for proper 16 bit mode in burst 2021-03-24 19:29:40 -04:00
David Sidrane d9d832c568 NuttX with BACKPORT libc/stdio: Preallocate the stdin, stdout and stderr 2021-03-24 18:27:30 -04:00
Daniel Agar ea902e7f38 systemcmds/tests: split out individual module test commands 2021-03-23 11:39:14 -04:00
David Sidrane 55abe48925 NuttX with BDMA enable fix backpork 2021-03-23 05:52:27 -07:00
Daniel Agar 5f6832e101 px4_work_queue: increasae UART stack 2021-03-22 22:48:58 -04:00
Beat Küng e2cd39bf6c micro_hal: use inline methods instead of #define's
Fixes errors in the form of 'error: statement has no effect'
2021-03-22 15:38:21 -04:00
Dongoo Lee 32012cb3ee for cmake option GENERATE_ROS_MODELS to make ROS sdf models 2021-03-22 08:59:48 +01:00
David Sidrane 833501dee6 stm32h7:adc fix temperature sensing 2021-03-19 15:48:47 +01:00
Daniel Agar 8f242ec444 cmake: add jlink_flash_uavcan_bin helper 2021-03-18 19:33:19 -04:00
David Sidrane e9409e59e6 NuttX with flexcan CTRL1 fixes backports 2021-03-18 21:38:56 +01:00
dinomani 4bf894a35d Update platforms/nuttx/src/px4/stm/stm32h7/include/px4_arch/micro_hal.h
Co-authored-by: David Sidrane <David.Sidrane@Nscdg.com>
2021-03-18 06:13:24 -07:00
dino 44b2e0b729 As David request 2021-03-18 06:13:24 -07:00
dino 7c8b7fa44d Fixed typo and added support for H7 temperature sense on ADC3 2021-03-18 06:13:24 -07:00
dino 6d04a67b02 Moving define to microhal.h files, for each ST architecture. Correct channels were verified with ST_CUBE header files. For the H7 its a simplification for the current used H7x3. Other devices in that family expect the temperarture on channel 18.
F1: channel 16
F3: channel 16
F4: channel 18
F7: channel 18
H7: channel 17, on STMf32Hx3
2021-03-18 06:13:24 -07:00
dino 528dc41822 changed #elif to #else, to build on all targets 2021-03-18 06:13:24 -07:00
dino 3c77ef7eb3 Fixed adc config, to read internal reference to get cpu temperature 2021-03-18 06:13:24 -07:00
Daniel Agar 385512aead uORB: test multi timestamp requirement only applies per topic instance 2021-03-17 12:35:53 -04:00
David Sidrane ccee36bb68 sd_bench and logger use aligned buffers 2021-03-17 05:27:53 +01:00
David Sidrane 45d0603627 micro_hal:Fixed DCACHE_LINESIZE abuse 2021-03-17 05:27:53 +01:00
David Sidrane 243adf5250 NuttX with SDMMC back ports 2021-03-16 15:37:41 -04:00
Daniel Agar 3c80db9796 boards: stm32f7 run gyro_fft by default 2021-03-15 09:42:35 -04:00
Daniel Agar 2257c3767e simple gyro auto calibration module 2021-03-15 09:46:47 +01:00
Daniel Agar 7fb43559f8 gyro_fft: run by default on STM32H7 2021-03-12 07:50:31 -05:00
Daniel Agar c356181f90 px4_work_queue: increase wq:rate_ctrl stack 2021-03-11 22:35:25 -05:00
Daniel Agar 6a6352577c cmake: nuttx error if GCC <= 7 2021-03-11 03:36:34 -08:00
Daniel Agar f725813128 add bootloader flash helper target (jlink_flash_bootloader) 2021-03-11 09:03:42 +01:00
David Jablonski 02abb760a3 SITL: add iris with fog-simulating lidar 2021-03-11 00:39:09 +01:00
Jaeyoung-Lim 0db29866f1 Add standard_vtol drop 2021-03-10 07:15:53 +01:00
Daniel Agar 4d288512b5 add board architecture specific init defaults 2021-03-09 19:59:41 +01:00
David Sidrane c792879612 Nuttx: PX4 Contrib Ethernet Hardening 2021-03-08 10:37:08 -05:00