* For some reason cppcheck complains with `fp != nullptr` but accepts truthiness
of handle by itself.
* Note that the expressions are equivalent according to the C++ standard ("A
prvalue of arithmetic, unscoped enumeration, pointer, or pointer to member
type can be converted to a prvalue of type bool. A zero value, null pointer
value, or null member pointer value is converted to false; any other value is
converted to true. A prvalue of type std::nullptr_t can be converted to a
prvalue of type bool; the resulting value is false.")
Using the hwvercmp on FMUv2 HW derivatives built with px4fmu_v3_default
to ues a more targeted startup approach:
1) Detect V3 and V2M
2) On V3 use the external mpu9250 to further discriminate between 2.0
and 2.1. Then only start the devices that are on that version of
the board.
3) Due to HW errata on PixhawkMini deprecate mpu9250.
The mpu9250 will not start reliably on the PixhawkMini
Since we have an ICM20608 and an External Mag the
mpu9250 is not to be used.
px4fmuv2 had PX4_SPIDEV_BMI defined, for the v3 cmake, but never
provided a Chip select decoded by PX4_SPIDEV_BMI. PX4_SPIDEV_BMI
has been removed from V2, but PX4_SPIDEV_EXT_BMI still remains
and has a chip select assigned to it.
The removes the alias so it is clear what bus and port bit
is associated with as CS or DRDY signal.
This becomes important when varients of V2 a) use the CS on differnt
busses or b) swap a RDY (in) for a CS (out). In both cases,
a CS on once buss, can back feed and cause sensor reset to not be
able to turn off the power if all the pins are not tunered
off
Pixhawk mini has reused the GPIO_SPI_CS_EXT1 signal that was associated
with SPI4. We can not in good faith assert a CS on a bus wer are not resetting.
So we must do this only on HW_VER_FMUV2MIN
Insure a 0.0 voltage initial condition on VDD_3V3_SENSORS
By starting the GPIO_VDD_3V3_SENSORS_EN, low and deferring
the GPIO init of the slave selects and drdy signals until
board_app_initialize. We get ~ 80 ms of power off time
with 0.00 voltage applied to the sensors.
1) Add hwtypecmp command to allow rc to further enumerate PX4FMU_V2
for sub types of 'V2' -FMUv2 'V2M' PixhawkMini, 'V30' Cube
2) Extend hw to report to display
HW type
HW version
HW revision
There are several boards that share the px4fmu-v2 build as px4fmu-v3 build.
It was initially envisioned, that the build would be binary compatable and
the RC script would probe different sensors and determine at runtime the
HW type. Unfortunately, a failed sensor, can result in mis-detection
of the HW and result in an improper start up and not detect the HW
failure.
All these boards's bootloader report board type as px4fmu-v2.
This precludes and automated selection of the correct fw if it
had been built, by a different build i.e. px4fmu-cube etc.
We need a way to deal with the slight differences in HW that effect
the operations of drivers and board level functions that are different
from the FMUv2 pinout and bus utilization.
1) FMUv3 AKA Cube 2.0 and Cube 2.1 Bothe I2C busses are external.
This effected the mag on GPS2 not reporting Internal and
having the wrong rotation applied.
2) FMUv3 does not performa a SPI buss reset correctly.
FMUv2 provides a SPI1 buss reset. But FMUv3 is on
SPI4. To complicate matters the CS cross bus
boundries.
3) PixhawkMini reused a signal that was associated with SPI4
as a SPI1 ready signal.
Based on hardware differnce in the use of PB4 and PB12 this code
detects: FMUv2, the Cube, and PixhawkMini and provides the
simple common API for retriving the type, version and revision.
On FmuV5 this same API will be used.
Per the data sheet: Start-up time for register read/write from power-up is
Typically 11 ms and the Maximum is 100 ms.
It seems the power up reset is only triggered at VDD < 150 mV. So the
symptom reported: Failure is only happening after a long power down is
consistent with VDD not dropping below 150 mV, therefore not generating
a POR and being ready to be written with out delay.
This fix adds a delay of 110 ms to ensure the reset has ended with some.
margin.
Juha Niskanen committed 326ab01 2017-06-20
STM32 F7: Set I2C4 SDA and SCL pins to open drain mode
Titus von Boxberg committed f3267dd 2017-07-17
I2C4_SDA can also be on GPIO PB7
Titus von Boxberg committed 28eab90 2017-07-27
No FSMC, only FMC for STM32F7
- avoids race conditions when geofence data is updated in flight. During
a transfer, the geofence module will not check for violations, which
is done with the new dm_trylock method.
- there is an update counter stored in dataman, and for each write
transaction this is increased, so that the geofence module can reload
the data upon data change (after it's unlocked).
- single dm item updates are atomic already, so resetting the polygons
to 0 does not need locking.