Ryan Johnston
c585758f67
boards/matek/gnss-m9n-f4: IMU orientation update
...
- the icm20602 needs to be rolled 180º and yaw 90º for this board.
2022-04-09 14:21:45 -04:00
Daniel Agar
6e9c673262
boards: omnibus_f4sd_ekf2 disable frsky telemetry to save flash (and fix build)
...
- this isn't great, but our options are limited at the moment and this
can be fixed later once the old mixing system is deleted
2022-04-05 11:10:33 -04:00
Hovergames
457130fb69
Support for NXP UWB position sensor
...
uwb_sr150 driver for the sensor, and some
modifications in precision landing to allow
landing on a platform using the UWB system.
2022-04-04 17:26:52 +02:00
Beat Küng
3381a5914d
holybro/kakuteh7: fix BOARD_FLASH_SIZE
...
The BL was reporting a flash size of 1703936, whereas it should be 1835008.
2022-04-04 10:44:11 -04:00
stmoon
179820cead
boards: px4_fmu_v5x_rtps disable common telemetry modules to save flash
2022-04-02 11:46:37 -04:00
Daniel Agar
803cc6814f
boards: px4_fmu-v2_fixedwing disable drivers/camera_trigger to save flash
2022-04-01 11:08:03 -04:00
Daniel Agar
f0be554857
boards: px4_fmu-v5_uavcanv0periph disable modules to save flash
2022-03-31 09:59:58 -04:00
Daniel Agar
82c1ffb8f8
boards: px4_fmu-v5_stackcheck disable common telemetry modules to save flash
2022-03-30 10:07:05 -04:00
CUAVmengxiao
1870b9245b
fmu-v5: add macro definitions for different version revisions
2022-03-29 17:09:34 -04:00
CUAVmengxiao
c0d5ae2f9f
fmu-v5: Add support for ICM-42688-P
2022-03-29 17:09:34 -04:00
Daniel Agar
dfe13e16e8
boards: px4_fmu-v2_multicopter disable distance_sensor/tfmini to save flash
2022-03-28 15:40:46 -04:00
Daniel Agar
67920f089b
boards: px4_fmu-v5x_rtps disable unused systemcmds and examples to save flash
2022-03-28 12:01:21 -04:00
Daniel Agar
5800c417c8
boards: px4_fmu-v2_rover disable unused drivers to save flash
2022-03-25 17:30:42 -04:00
Daniel Agar
eb666e94a4
bords: omnibus_f4sd move ekf2 from default to new ekf2 board variant
...
- temporary solution to flash overflow
2022-03-25 12:47:25 -04:00
David Sidrane
9fe2dfc2e3
px4_fmuv-6x Sensor set 3
2022-03-23 12:24:31 -04:00
Daniel Agar
94e30f5efb
boards: delete unused px4_fmu-v2_test
2022-03-23 10:39:58 -04:00
Daniel Mesham
06a9be74fa
microdds: add xrce client
2022-03-22 09:01:05 +01:00
Daniel Agar
c86d5769ea
boards: px4_fmu-v2_{fixedwing,multicopter} module selection changes to save flash
2022-03-19 14:43:45 -04:00
Jukka Laitinen
4658a627d7
Separate i2c and spi board bus configuration into and own library for protected build target
...
This info is needed on both kernel and user sides, and is just data.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-03-17 08:01:51 +01:00
Jukka Laitinen
56c6120e83
Use IOCTL for board_read_VBUS_state in NuttX protected builds
...
Direct gpio read is not possible from user side applications, so use boardctl
interface instead.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-03-17 08:01:51 +01:00
Jukka Laitinen
0cf3079401
px4_fmuv5: Implement BOARD_*_LOCKOUT_STATE in protected/kernel builds
...
In memory protected builds these perform nuttx boardctl ioctl calls to kerenel
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-03-17 08:01:51 +01:00
Jukka Laitinen
356328056a
Add px4_fmu-v5_protected target
...
Add a target for nuttx protected build development
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-03-17 08:01:51 +01:00
Daniel Agar
4746a19c0c
boards: px4_fmu-v5_stackcheck disable UUV modules to save flash
2022-03-15 12:10:03 -04:00
bresch
58bd3d0c60
cmake: use elif -> elseif
2022-03-11 11:59:20 +01:00
alessandro
0617fd2b6f
fmu-v6x: increase UART5 buffer size
...
The same fix had to be done for the fmu-v5x:
PX4/PX4-Autopilot#14932
2022-03-09 08:39:34 -05:00
Beat Küng
601c588294
holybro/kakuteh7: disable bluetooth
2022-03-04 08:02:11 -05:00
Beat Küng
047352d049
holybro/kakuteh7: update bootloader binary
2022-03-04 08:02:11 -05:00
Bulut Gözübüyük
80c6ab7106
Add support for Omnibus F4 boards with ICM20608G IMUs
...
One can use following command to compile:
make omnibus_f4sd_icm20608g
Co-Authored-By: berkercanatar <19846944+berkercanatar@users.noreply.github.com>
2022-03-04 08:27:48 +01:00
Beat Küng
3e6a35fe8a
px4/fmu-v2/rover: disable module to reduce flash
2022-02-25 08:30:58 +01:00
Beat Küng
29d5dd9b8f
omnibus/f4sd: disable module to reduce flash
2022-02-25 08:30:58 +01:00
Beat Küng
bc9dfe8599
holybro/kakutef7: disable module to reduce flash
2022-02-25 08:30:58 +01:00
Beat Küng
e10ff59340
px4/fmu-v5/stackcheck: disable module to reduce flash
2022-02-25 08:30:58 +01:00
Daniel Agar
611d50edf3
boards: holybro kakutef7 disable tone_alarm to save flash
2022-02-24 11:33:25 -05:00
Daniel Agar
5b5d428189
boards: px4_fmu-v5_stackcheck disable fake_gps to save flash
2022-02-23 10:44:09 -05:00
Daniel Agar
01daf8d6d6
boards: omnibus_f4sd disable events module to save flash
2022-02-23 10:42:48 -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
Daniel Agar
3c58932aff
boards: px4_fmu-v2_default disable ms4525 to save flash
2022-02-21 16:45:22 -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
Daniel Agar
8489cec08f
boards: spracing h7extreme keep icm42688p in RAM
...
- to make space move rc_update itcm -> sram
2022-02-17 10:30:14 -05:00
Daniel Agar
9aca693945
boards: spracing h7extreme add alternate IMU icm42688p
2022-02-17 10:30:14 -05:00
Daniel Agar
abfa3d23a5
boards: matek h743-slim fix STM32_SDMMC_SDXFR_CLKDIV typo
2022-02-16 10:28:01 -05:00
David Sidrane
1c66fb44aa
holybro_kakutef7:fit in flash
2022-02-16 10:09:02 -05:00
David Sidrane
2e67b92b4d
px4_fmu-v5_stackcheck:Fit in flash
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
David Sidrane
b5916ac712
px4_fmu-v6x:Document the DMA usage
2022-02-16 10:09:02 -05:00
David Sidrane
7eefdd1e3d
px4_fmu-v6x:Enable DMA on TELEM{1|2}
2022-02-16 10:09:02 -05:00
Charles Cross
f9feb04f8b
Changes SDIO clock speed to 20MHz for the Matek H743 slim
...
Signed-off-by: Charles Cross <charles@missionrobotics.us>
2022-02-15 09:38:09 -08:00
Nico van Duijn
10ad553f1d
v5x: add battery_status module to enable analog bat sensing
2022-02-09 16:54:45 -05:00
Beat Küng
28c27f1b9a
px4/fmu-v5x: add ADC_ADS1115_EN param to use external ADC
2022-02-09 16:54:45 -05:00
David Sidrane
fd1aa3cfb9
matek_gnss-m9n-f4:Use CONFIG_BOARD_SERIAL_GPSn for serial_passthru
2022-02-09 13:11:52 -05:00
David Sidrane
0c936e4fd2
serial_passthru:Move CONFIG_xxx to serial_passthru
2022-02-09 13:11:52 -05:00
Oleg Kalachev
21b78f9d05
Enable mpu9250’s magnetometer on fmu-v4
2022-02-08 13:18:39 -05:00
Viktor Vladic
f4d02a2937
MatekH743 board_id, usb vid/pid changes, and MPU6000 delay before transfer - not after ( #18733 )
...
* Make board_id compatible with ardupilot
* Initialize outputs for CAM1/CAM2 and Vsw pad
* Correct board type 1013 in bootloader to match AP
* Change usb vendor string to "Matek"
* Change cdcacm pid to 1013
* Comment out FLASH_BASED_PARAMS because of #15331
2022-02-07 19:55:49 -05:00
Julian Oes
490a0c473b
Rename vmount to gimbal
2022-02-07 19:21:15 -05:00
Daniel Agar
052adfbfd9
borads: holybro_kakutef7 disable modules/events to save flash
2022-02-06 16:53:13 -05:00
Daniel Agar
3a741cb9c9
boards: bitcrazy_crazyflie disable gyro_fft to save flash
2022-02-06 16:53:13 -05:00
David Sidrane
ec441fdba6
gnss-m9n-f4:Add serial_passthru
2022-02-01 21:49:29 -05:00
David Sidrane
0c8a5b3da1
matek-gnss-m9n-f4:Enable IO compensation
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
dirksavage88
d92244b664
Initial Matek m9nf4 can node support
...
Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
Added uavcan board identity
Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
Added usb.c, LED rework may be needed
Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
PX4 dates added to all files
Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
Matek M9NF4 CAN Node initial board support
Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
Changed GPS to ttyS3 in board sensors, led board on/off definitions
Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
Added app descriptor section to canbootloader linker script
Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
Changed board naming convention to match vendor
Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
Changed canbootloader and nsh menuconfig
Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
Test defconfig changes, IRQ hardfault in bootloader
Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
Working canbootloader, App firmware stil WIP
Working App firmware: changed romfsroot to 'cannode', TODO: verify GPS & IMU config
Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
TODO: Debug GPS no sats/low sats issue, no magnetometer on some boards
Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
2022-02-01 21:49:29 -05:00
Jukka Laitinen
f8a090e85e
Remove HYGROMETERS from fmu-v5 stackcheck build and rename to COMMON_HYGROMETERS
...
The stackcheck build flash space overflows after adding hygrometers.
Also follow the naming convention of other similar config flags, and rename the
config.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-02-01 08:56:25 -05:00
Roman Dvořák
ed475ca324
SHT3x driver
...
SHT3x driver, clean code
changes leading to merge TFHT with CUAV hygrometer
Delete humidity_temperature.msg
Update CMakeLists.txt
rename 'atmosphefir_quantities' to 'hygrometers'
fix logging
removed cmake files
fix PR issues
2022-01-31 21:38:26 -05:00
Jukka Laitinen
1f9ace3901
boards/px4/fmu-v5: Add linker scripts for kernel-userspace split
...
These scripts are used in protected build configuration
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-01-31 20:26:08 -05:00
Jukka Laitinen
03c0a2d56c
Fix some cmake / linker depenencies for boards
...
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2022-01-27 12:42:40 -05:00
Jukka Laitinen
700c13cdff
Remove linking of arch_io_pins into drivers_board
...
This goes the other way around; arch_io_pins is using the pin
definitions from drivers_board, so the drivers_board needs to be linked
into arch_io_pins
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
Beat Küng
425b268feb
boards: add holybro/kakuteh7
...
known issues:
- flash-based params does not work on H7 (due to ECC), so params are on
SD card. The last flash sector is still reserved however.
- output channel 6 does not support DShot (the implementation does not
handle channel gaps)
- flashing of the 2. flash bank is much slower (around 3x), than the 1.
bank for some unknown reason.
- after the BL jumps to the app, there's several seconds passing until
stm32_boardinitialize() is called.
2022-01-17 10:41:33 -05:00
David Sidrane
25099ce11f
fmurt1062-v1:Added GPS driver dropped in move to boardconfig
2022-01-14 07:04:06 -08:00
alexklimaj
d1304e1ceb
Add CANNODE_GPS_RTCM
2022-01-12 15:30:38 -05:00
Julian Oes
6ed48ad0c0
ROMFS: Remove now unused variable
2022-01-10 23:04:10 -05:00
Julian Oes
38439256e5
Mantis: move MIXER vars to airframe init
...
The two were actually conflicting and are now consolidated.
2022-01-10 23:04:10 -05:00
Julian Oes
14fb019821
Mantis: move SYS_DM_BACKEND to board_defaults
...
Otherwise it is set too late and not used during startup.
2022-01-10 23:04:10 -05:00
Julian Oes
feb2987fa8
Mantis: remove unused transition script
...
When coming from the previous stack there are no params anywhere, so
this will not execute anyway.
2022-01-10 23:04:10 -05:00
Julian Oes
b3d830dd11
Mantis: move power off tune to commander
...
This way we don't allocate inside the interrupt context.
2022-01-10 23:04:10 -05:00
Julian Oes
372a0da987
Mantis: move upload.sh into boards/atl/mantis-edu
2022-01-10 23:04:10 -05:00
Julian Oes
0ffdccbd60
Mantis: Add MPC2520 again
2022-01-10 23:04:10 -05:00
Julian Oes
b44f5b49ca
Mantis: add tap_esc to Kconfig
2022-01-10 23:04:10 -05:00
Julian Oes
8331339927
atl_mantis: update bootloader binary again
...
This includes the fix which disables the UART overrun.
2022-01-10 23:04:10 -05:00
Julian Oes
b92aa92bec
Mantis: fix mixer loading
...
The ordering before did not work out, and without the sleep it fails.
2022-01-10 23:04:10 -05:00
Julian Oes
06b5b58b3b
Mantis: increase Tx buffer to with gimbal->camera
...
This way log streaming works with much less drops.
2022-01-10 23:04:10 -05:00
Julian Oes
11b60904c3
Mantis: use lower log streaming rate
2022-01-10 23:04:10 -05:00
Julian Oes
f3a278dce5
Mantis: add comment about boot order.
...
The boot order is now:
1. The PX4 bootloader boots, and starts the camera.
2. The camera starts and sends the boot command to the PX4 bootloader.
3. PX4 starts.
2022-01-10 23:04:10 -05:00
Julian Oes
ecfc7cc24f
Mantis: set bootloader timeout to 180 seconds
...
The first byte 0xb4 is 180. This number is read by the bootloader.
2022-01-10 23:04:10 -05:00
Julian Oes
e15cbc3a6b
Mantis: move tap_esc to extras
...
This way we work around an issue where tap_esc got stuck during bootup
in a cold boot.
2022-01-10 23:04:10 -05:00
Julian Oes
e4763f15f6
Mantis: add RC hacks
...
This changes the way RC is handled for the Mantis:
- The RC values are re-written when arriving over MAVLink. They are
rescaled from 0..4095 to 1000..2000 and the channel bits added to
separate channels. This makes the downstream handling easier.
- Gimbal pitch is moved from Aux1 to Aux2 as that should be the default.
- Aux3 and Aux4 are used for the photo and video trigger.
- The speed button is used as the FLTMODE channel and set to switch
between POSCTL and ALTCTL.
2022-01-10 23:04:10 -05:00
Julian Oes
1754e25920
vmount: add param to use RC input for angular rate
...
Until now RC input was translated to angles only. I added the param
MNT_RC_IN_MODE which allows the RC input to be used for angular rate.
2022-01-10 23:04:10 -05:00
Julian Oes
f03990f015
Mantis: prevent output setup from running
...
This is not required as we start tap_esc directly and load the mixer.
2022-01-10 23:04:10 -05:00
Julian Oes
cb15728536
Mantis: save mission in RAM
...
This is using a reduced number of mission items of 1000 instead of 2000
in order to fit in RAM.
2022-01-10 23:04:10 -05:00
Julian Oes
a50f7af3b1
Mantis: update bootloader and SYS_AUTOSTART
...
This adds a check for the previous SYS_AUTOSTART id. If it is still the
old/previous SYS_AUTOSTART id, it will flash the new bootloader as well
as set the proper SYS_AUTOSTART id.
2022-01-10 23:04:10 -05:00
Julian Oes
4a43155e69
Mantis: remove duplicate define
2022-01-10 23:04:10 -05:00
Julian Oes
7759ffb00e
Mantis: reduce power button hold time
...
This is more intuitive and matches the tune.
Hopefully, it's still long enough to prevent any false positives.
2022-01-10 23:04:10 -05:00
Julian Oes
6960600c28
Mantis: play power off tune
...
To play a power off tune, I needed to convert the file to C++, so that I
could use the uORB::Publication.
The current implementation starts playing the power off sound but then
stops it as soon as the button is released.
The problem is mostly that we only get an interrupt when the button is
pressed or released but we don't seem to be able to poll it, at least
not in the current state.
2022-01-10 23:04:10 -05:00
Julian Oes
de1849167d
Mantis: Add upload_wifi target to upload firmware
2022-01-10 23:04:10 -05:00
Daniel Agar
d077ca15fb
delete PWM_SERVO_SET, PWM_SERVO_SET_MODE, systemcmds/motor_ramp, and pwm_out test
2022-01-10 09:51:11 -05:00
Daniel Agar
df44df2df6
delete systemcmds/esc_calib
...
- this is redundant with commander esc_calibration
2022-01-10 09:51:11 -05:00
Daniel Agar
daa925137c
boards: move default battery calibration defines to parameter defaults
2022-01-10 09:49:36 -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
Daniel Agar
e835a7c4ea
boards: enable readline history and tab completion on newer boards
2022-01-03 10:44:32 -05: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
77b65ee564
boards: px4_fmu-v5_debug disable stack check
...
- this is redundant with px4_fmu-v5_stackcheck
2021-12-31 19:34:18 -05:00
Daniel Agar
6d0339ba0c
I2CSPIDriverBase: sensor start failure ERROR if internal, WARN if external
2021-12-28 11:05:35 -05:00
Daniel Agar
990d7c159d
pwm_out: cleanup and prep for linux compatibility
2021-12-28 11:04:00 -05:00
Daniel Agar
10f4a2e91f
boards: omnibus_f4sd_default disable systemcmds to save flash
2021-12-27 12:19:55 -05:00
Daniel Agar
3ef9c2d16c
boards: holybro_kakutef7_default disable modules/gyro_calibration to save flash
2021-12-27 12:19:55 -05:00
Daniel Agar
3f17acdcc9
boards: mro_ctrl-zerl-h7-oem pin fixes (sync with mro_ctrl-zero-h7)
2021-12-27 09:25:21 -05:00
Daniel Agar
0f4e1dd9f9
boards: mro ctrl-zero-h7 pin fixes
2021-12-27 09:25:21 -05:00
Daniel Agar
98d706772e
boards: px4_fmu-v2_rover disable events module to save flash
2021-12-24 20:06:13 -05:00
Beat Küng
9bc9169b77
px4/fmu-v5x: add missing board variants to rc.board_mavlink
2021-12-24 20:06:13 -05:00
Beat Küng
6c8f322dfe
px4/fmu-v2/test: disable modules to reduce flash
2021-12-24 20:06:13 -05:00
Beat Küng
082cd74cab
holybro/kakutef7: disable IST8310 to reduce flash
2021-12-24 20:06:13 -05:00
Beat Küng
8743b78474
px4/fmu-v2/rover: disable modules to reduce flash
2021-12-24 20:06:13 -05:00
Beat Küng
0818bb4be0
bitcraze/crazyflie{,21}: disable modules to reduce flash
2021-12-24 20:06:13 -05:00
Beat Küng
751539304e
omnibus/f4sd: disable modules to reduce flash
2021-12-24 20:06:13 -05:00
Daniel Agar
c8f2a29d67
boards: beaglebone_blue_default fix missing linux_pwm_out driver
2021-12-23 15:57:11 -05:00
Daniel Agar
a5f58d321e
boards: emlid_navio_default fix missing drivers/modules
2021-12-23 15:57:11 -05:00
Julian Oes
9686c81f7d
boards: enable flow control on CDCACM
...
This enables flow control on CDCACM for the NuttX boards which fixes a
problem where HITL would stall.
The stall could happen if the hardware would be a bit too slow in
keeping up with the incoming messages. Often, this happened on arming
because the logger would take some time to log all parameters right at
the beginning.
The stall would then not recover due to NuttX bug where the rx interrupt
would not be restored correctly and instead only a slower watchdog would
release the next read. This watchdog takes 200ms which means it's hard
to impossible to get out of the situation without restarting sim and/or
PX4. For more information about the issue, see:
apache/incubator-nuttx#3633
As a workaround, until that bug is fixed, and because it makes sense
anyway, I propose to enable FLOWCONTROL for the serial via USB.
2021-12-21 08:01:38 +01:00
Beat Küng
87ec8839c4
px4/fmu-v5x: remove unused base_phy_DP83848C build variant
2021-12-10 09:03:08 -05:00
Beat Küng
ca6df035b4
px4/fmu-v5x: add arch_io_pins dependency (required in init.cpp)
2021-12-10 09:03:08 -05:00
Daniel Agar
8185e2a384
boards: board_app_initialize() don't return early on failure
...
- depending on the situation we're more likely to get actionable user
feedback by allowing boot to complete rather than silently failing
2021-12-09 20:41:54 -05:00
Cindy Hsieh
ca90c785e9
correct pin in the comment, no code changed
2021-12-09 20:40:34 -05:00
Matthias Grob
fdc40880d0
battery: separate out publishing from updating
...
to allow smart battery drivers to use the battery class and
filling in additional information in case it makes sense.
2021-12-07 21:06:51 +01:00
Matthias Grob
e70d70468a
battery: pass voltage and current by setter
2021-12-07 21:06:51 +01:00
Matthias Grob
39641494da
battery: pass connected flag in by setter
2021-12-07 21:06:51 +01:00
Matthias Grob
38d23f5345
battery: pass priority in by setter
2021-12-07 21:06:51 +01:00
Matthias Grob
f9fc9a9af6
battery: pass source in by constructor
2021-12-07 21:06:51 +01:00
Matthias Grob
b965923c08
battery: fetch throttle value inside of class
2021-12-07 21:06:51 +01:00
Daniel Agar
4bf1b46e47
boards: free up flash on crazyflie and omnibus
2021-12-06 09:37:08 -05:00
Daniel Agar
3160e7a3cd
Jenkins: run calib_udelay on test rack
2021-12-05 19:42:10 -05:00
Daniel Agar
713350930d
boards: px4_fmu-v5 add test variant
2021-12-05 18:08:54 -05:00
Daniel Agar
37c1598f38
boards: cubepilot_cubeorange enable calib_udelay and run on test rack
2021-12-05 14:50:03 -05:00
Daniel Agar
7d515e3d58
boards: cubepilot_cubeorange lower cpu clock 480 -> 400 MHz to reduce temperature
2021-12-05 14:50:03 -05:00
Daniel Agar
a2064cceff
boards: enable early MPU reset on any board potentially not using the PX4 bootloader
2021-12-01 20:13:41 -05:00
Peter van der Perk
36ba8cc6dd
UAVCANv1 update FMU-V5 config
2021-12-01 09:29:15 -05:00
Peter van der Perk
ce909b23b1
UAVCANv1 Node implementation work, PNP, Registers and uORB publisher
2021-12-01 09:29:15 -05:00
David Sidrane
76585409fa
durandal rev 1 has bmi088->icm20602
2021-11-29 21:59:30 -05:00
benjinne
38e7f814d5
mro h7 boards add rtps px4board files
2021-11-29 21:50:32 -05:00
David Sidrane
df1c94dd4e
px4_fmu-v5_debug:Increase stack size
2021-11-29 16:01:08 -05:00
Jukka Laitinen
c2cbab1e98
Improve stub_keystore configuration
...
It is possible to either set the keyfile locations in board configuration or
with the same environment variables as before.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
2021-11-29 11:09:51 -05:00
Daniel Agar
9b7c8c8a8b
boards: px4_fmu-v6x_default enable ethernet by default with NuttX optimizations
2021-11-29 09:08:42 -05:00
Daniel Agar
b9152dc4d0
boards: px4_fmu-v5x_default increase ETH pktsize to max and enable tcp delayed ack
2021-11-29 09:08:42 -05:00
Daniel Agar
0459b73520
boards: px4_fmu-v5x enable mavlink ethernet by default
2021-11-29 09:08:42 -05:00
David Sidrane
e507563911
uvify_core nsh:Remove CONFIG_RAMTRON_WRITEWAIT
2021-11-26 19:27:29 -05:00
David Sidrane
23c73d4e0b
px4_fmu-v6x nsh:Remove CONFIG_RAMTRON_WRITEWAIT
2021-11-26 19:27:29 -05:00
David Sidrane
51b55533af
px4_fmu-v6u nsh:Remove CONFIG_RAMTRON_WRITEWAIT
2021-11-26 19:27:29 -05:00
David Sidrane
b8bdf7e1c4
px4_fmu-v5x nsh:Remove CONFIG_RAMTRON_WRITEWAIT
2021-11-26 19:27:29 -05:00
David Sidrane
3504541ebd
px4_fmu-v5x base_phy_DP83848C:Remove CONFIG_RAMTRON_WRITEWAIT
2021-11-26 19:27:29 -05:00
David Sidrane
60229c28a8
px4_fmu-v5 uavcanv1:Remove CONFIG_RAMTRON_WRITEWAIT
2021-11-26 19:27:29 -05:00
David Sidrane
01681d6b47
px4_fmu-v5 stackcheck:Remove CONFIG_RAMTRON_WRITEWAIT
2021-11-26 19:27:29 -05:00
David Sidrane
32c2160137
px4_fmu-v5 nsh:Remove CONFIG_RAMTRON_WRITEWAIT
2021-11-26 19:27:29 -05:00
David Sidrane
cf36435ed3
px4_fmu-v5 debug:Remove CONFIG_RAMTRON_WRITEWAIT
2021-11-26 19:27:29 -05:00