mirror of https://github.com/ArduPilot/ardupilot
AP_BoardConfig: added get_board_type() for PX4
used to decide what drivers to start
This commit is contained in:
parent
e91b1318fb
commit
ce174489c3
|
@ -55,12 +55,21 @@ public:
|
|||
VRX_BOARD_CORE10 = 11,
|
||||
VRX_BOARD_BRAIN54 = 12,
|
||||
#endif
|
||||
PX4_BOARD_TEST_V1 = 101,
|
||||
PX4_BOARD_TEST_V2 = 102,
|
||||
PX4_BOARD_TEST_V4 = 104,
|
||||
};
|
||||
#endif
|
||||
|
||||
// set default value for BRD_SAFETY_MASK
|
||||
void set_default_safety_ignore_mask(uint16_t mask);
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
static enum px4_board_type get_board_type(void) {
|
||||
return px4_configured_board;
|
||||
}
|
||||
#endif
|
||||
|
||||
private:
|
||||
AP_Int16 vehicleSerialNumber;
|
||||
|
||||
|
@ -79,6 +88,9 @@ private:
|
|||
#endif
|
||||
AP_Int8 board_type;
|
||||
} px4;
|
||||
|
||||
static enum px4_board_type px4_configured_board;
|
||||
|
||||
void px4_drivers_start(void);
|
||||
void px4_setup(void);
|
||||
void px4_setup_pwm(void);
|
||||
|
|
|
@ -33,6 +33,8 @@
|
|||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
AP_BoardConfig::px4_board_type AP_BoardConfig::px4_configured_board;
|
||||
|
||||
/*
|
||||
declare driver main entry points
|
||||
*/
|
||||
|
@ -692,6 +694,15 @@ void AP_BoardConfig::vrx_start_optional_sensors(void)
|
|||
|
||||
void AP_BoardConfig::px4_setup_drivers(void)
|
||||
{
|
||||
if (px4.board_type == PX4_BOARD_TEST_V1 ||
|
||||
px4.board_type == PX4_BOARD_TEST_V2 ||
|
||||
px4.board_type == PX4_BOARD_TEST_V4) {
|
||||
// use in-tree drivers
|
||||
printf("Using in-tree drivers\n");
|
||||
px4_configured_board = (enum px4_board_type)px4.board_type.get();
|
||||
return;
|
||||
}
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
px4_start_common_sensors();
|
||||
switch ((px4_board_type)px4.board_type.get()) {
|
||||
|
@ -746,6 +757,8 @@ void AP_BoardConfig::px4_setup_drivers(void)
|
|||
|
||||
#endif // HAL_BOARD_PX4
|
||||
|
||||
px4_configured_board = (enum px4_board_type)px4.board_type.get();
|
||||
|
||||
// delay for 1 second to give time for drivers to initialise
|
||||
hal.scheduler->delay(1000);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue