This insures the common exception handler will not be
re-entered. The handler does not support nested interrupts
and the interrupt stack pointer and context will be overwritten
resulting in hard to debug hardfaults.
If all the priorities are equal the NVIC prevents the
preemption. The startup code defaults all the priorities
to the same value 128.
This change safeguards in 2 ways 1) By disabling
CONFIG_ ARCH_IRQPRIO: up_prioritize_irq cannot be called.
This will insure that all HW interrupts are at the same
priority.
2) By disabling CONFIG_ARCH_HIPRI_INTERRUP, the common
exception will disable any interrupts during interrupt
processing.
This fixes automatic upload. Since ed95dced0f the NuttX string
is used for device detection, but Linux uses the bootloader's USB vendor
and product strings.
So the NuttX strings must match with the ones from the bootloader.
Flight tested: ekf2 w/ mag and compass by @nathantsoi: https://logs.px4.io/plot_app?log=79b81031-cf1e-41f0-890b-d6cd7d559766
NOTE: external I2C devices need a pullup. I have tested with a 3.3v 2.2k pullup.
Working:
- mpu6000, bench tested and verified via nsh
- fmu
- all 6 ch output bench tested w/ pwm and oneshot via nsh
- ppm input bench tested
- dsm input bench tested
- bmp280, bench tested and verified via nsh
- hmc5883, bench tested and verified via nsh, but requires an external i2c pullup
- gps on uart6
- startuplog, nsh, mavlink on uart4, but params are not sent for some reason. RSSI pin is TX, MOTOR 5 is RX (normal mode, 57600 baud)
- rgbled over i2c, bench tested and workingp
- sbus via the shared sbus/ppm pin (which includes an inverter to the mcu SBUS in pin), remove the solder bridge or jumper to the ppm pin before use
Not yet implemented:
- ADC
- OSD: passthrough video is untested, use at your own risk until a basic driver is implemented.
Log file download via Mavlink is the one that needs the most bandwidth.
It needs typically around 200B TX buffer, and spikes at around 1500B every
10sec, with an average download speed of 230KB/s.
This saves almost 2kb of RAM when using the mavlink shell. 70 matches the
size of the mavlink message. Since the pipe is blocking, a process writing
a lot of data will just wait, data will not be dropped.
The mavlink shell is the only process creating a pipe.