mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_BoardConfig: moved optional sensors to the sensor startup
this makes startup much faster
This commit is contained in:
parent
36e0c7229a
commit
7806aa4274
@ -33,6 +33,11 @@ public:
|
|||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
|
// public method to start a driver
|
||||||
|
static bool px4_start_driver(main_fn_t main_function, const char *name, const char *arguments);
|
||||||
|
#endif
|
||||||
|
|
||||||
private:
|
private:
|
||||||
AP_Int16 vehicleSerialNumber;
|
AP_Int16 vehicleSerialNumber;
|
||||||
|
|
||||||
@ -68,7 +73,6 @@ private:
|
|||||||
void px4_setup_drivers(void);
|
void px4_setup_drivers(void);
|
||||||
void px4_sensor_error(const char *reason);
|
void px4_sensor_error(const char *reason);
|
||||||
|
|
||||||
bool px4_start_driver(main_fn_t main_function, const char *name, const char *arguments);
|
|
||||||
void px4_start_common_sensors(void);
|
void px4_start_common_sensors(void);
|
||||||
void px4_start_fmuv1_sensors(void);
|
void px4_start_fmuv1_sensors(void);
|
||||||
void px4_start_fmuv2_sensors(void);
|
void px4_start_fmuv2_sensors(void);
|
||||||
|
@ -60,10 +60,6 @@ extern "C" {
|
|||||||
int trone_main(int, char **);
|
int trone_main(int, char **);
|
||||||
int mb12xx_main(int, char **);
|
int mb12xx_main(int, char **);
|
||||||
int pwm_input_main(int, char **);
|
int pwm_input_main(int, char **);
|
||||||
int oreoled_main(int, char **);
|
|
||||||
int batt_smbus_main(int, char **);
|
|
||||||
int irlock_main(int, char **);
|
|
||||||
int px4flow_main(int, char **);
|
|
||||||
int uavcan_main(int, char **);
|
int uavcan_main(int, char **);
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -445,29 +441,10 @@ void AP_BoardConfig::px4_start_optional_sensors(void)
|
|||||||
if (px4_start_driver(mb12xx_main, "mb12xx", "start")) {
|
if (px4_start_driver(mb12xx_main, "mb12xx", "start")) {
|
||||||
printf("Found mb12xx sensor\n");
|
printf("Found mb12xx sensor\n");
|
||||||
}
|
}
|
||||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) || defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
|
||||||
if (px4_start_driver(px4flow_main, "px4flow", "start")) {
|
|
||||||
printf("Found px4flow sensor\n");
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (px4_start_driver(pwm_input_main, "pwm_input", "start")) {
|
if (px4_start_driver(pwm_input_main, "pwm_input", "start")) {
|
||||||
printf("started pwm_input driver\n");
|
printf("started pwm_input driver\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
|
||||||
if (px4_start_driver(oreoled_main, "oreoled", "start autoupdate")) {
|
|
||||||
printf("oreoled started OK\n");
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (px4_start_driver(batt_smbus_main, "batt_smbus", "-b 2 start")) {
|
|
||||||
printf("Found batt_smbus\n");
|
|
||||||
}
|
|
||||||
|
|
||||||
if (px4_start_driver(irlock_main, "irlock", "start")) {
|
|
||||||
printf("irlock started\n");
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user