mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
AP_BoardConfig: work around issues with bad components on some FMUv4 boards
some pixracer copies have poor components which can cause sensor bus brownout on boot. This resets the sensor bus for 20ms on boot to try to get clean sensor startup
This commit is contained in:
parent
9b89b4f561
commit
aa4cde1aae
@ -51,6 +51,7 @@ extern "C" {
|
||||
int mb12xx_main(int, char **);
|
||||
int pwm_input_main(int, char **);
|
||||
int uavcan_main(int, char **);
|
||||
int fmu_main(int, char **);
|
||||
};
|
||||
|
||||
|
||||
@ -468,6 +469,17 @@ void AP_BoardConfig::px4_start_fmuv4_sensors(void)
|
||||
*/
|
||||
void AP_BoardConfig::px4_start_common_sensors(void)
|
||||
{
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V4)
|
||||
/*
|
||||
this works around an issue with some FMUv4 hardware (eg. copies
|
||||
of the Pixracer) which have incorrect components leading to
|
||||
sensor brownout on boot
|
||||
*/
|
||||
if (px4_start_driver(fmu_main, "fmu", "sensor_reset 20")) {
|
||||
printf("FMUv4 sensor reset complete\n");
|
||||
}
|
||||
#endif
|
||||
|
||||
if (px4_start_driver(ms5611_main, "ms5611", "start")) {
|
||||
printf("ms5611 started OK\n");
|
||||
} else {
|
||||
|
Loading…
Reference in New Issue
Block a user