mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_BoardConfig: moved optional sensor startup out of AP_BoardConfig
This commit is contained in:
parent
950fde477d
commit
08f770125e
@ -46,6 +46,7 @@ public:
|
|||||||
PX4_BOARD_PIXRACER = 4,
|
PX4_BOARD_PIXRACER = 4,
|
||||||
PX4_BOARD_PHMINI = 5,
|
PX4_BOARD_PHMINI = 5,
|
||||||
PX4_BOARD_PH2SLIM = 6,
|
PX4_BOARD_PH2SLIM = 6,
|
||||||
|
PX4_BOARD_OLDDRIVERS = 100,
|
||||||
#endif
|
#endif
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||||
VRX_BOARD_BRAIN51 = 7,
|
VRX_BOARD_BRAIN51 = 7,
|
||||||
@ -55,9 +56,6 @@ public:
|
|||||||
VRX_BOARD_CORE10 = 11,
|
VRX_BOARD_CORE10 = 11,
|
||||||
VRX_BOARD_BRAIN54 = 12,
|
VRX_BOARD_BRAIN54 = 12,
|
||||||
#endif
|
#endif
|
||||||
PX4_BOARD_TEST_V1 = 101,
|
|
||||||
PX4_BOARD_TEST_V2 = 102,
|
|
||||||
PX4_BOARD_TEST_V3 = 103
|
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -111,7 +109,6 @@ private:
|
|||||||
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);
|
||||||
void px4_start_optional_sensors(void);
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||||
@ -122,7 +119,6 @@ private:
|
|||||||
void vrx_start_ubrain52_sensors(void);
|
void vrx_start_ubrain52_sensors(void);
|
||||||
void vrx_start_core10_sensors(void);
|
void vrx_start_core10_sensors(void);
|
||||||
void vrx_start_brain54_sensors(void);
|
void vrx_start_brain54_sensors(void);
|
||||||
void vrx_start_optional_sensors(void);
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif // HAL_BOARD_PX4 || HAL_BOARD_VRBRAIN
|
#endif // HAL_BOARD_PX4 || HAL_BOARD_VRBRAIN
|
||||||
|
@ -45,10 +45,6 @@ extern "C" {
|
|||||||
int l3gd20_main(int , char **);
|
int l3gd20_main(int , char **);
|
||||||
int lsm303d_main(int , char **);
|
int lsm303d_main(int , char **);
|
||||||
int hmc5883_main(int , char **);
|
int hmc5883_main(int , char **);
|
||||||
int ll40ls_main(int, char **);
|
|
||||||
int trone_main(int, char **);
|
|
||||||
int mb12xx_main(int, char **);
|
|
||||||
int pwm_input_main(int, char **);
|
|
||||||
int uavcan_main(int, char **);
|
int uavcan_main(int, char **);
|
||||||
int fmu_main(int, char **);
|
int fmu_main(int, char **);
|
||||||
int px4io_main(int, char **);
|
int px4io_main(int, char **);
|
||||||
@ -376,9 +372,6 @@ void AP_BoardConfig::px4_start_fmuv2_sensors(void)
|
|||||||
if (have_FMUV3) {
|
if (have_FMUV3) {
|
||||||
// on Pixhawk2 default IMU temperature to 60
|
// on Pixhawk2 default IMU temperature to 60
|
||||||
_imu_target_temperature.set_default(60);
|
_imu_target_temperature.set_default(60);
|
||||||
px4.board_type.set_and_notify(PX4_BOARD_PIXHAWK2);
|
|
||||||
} else {
|
|
||||||
px4.board_type.set_and_notify(PX4_BOARD_PIXHAWK);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
printf("FMUv2 sensors started\n");
|
printf("FMUv2 sensors started\n");
|
||||||
@ -403,7 +396,6 @@ void AP_BoardConfig::px4_start_fmuv1_sensors(void)
|
|||||||
} else {
|
} else {
|
||||||
px4_sensor_error("mpu6000");
|
px4_sensor_error("mpu6000");
|
||||||
}
|
}
|
||||||
px4.board_type.set_and_notify(PX4_BOARD_PX4V1);
|
|
||||||
#endif // CONFIG_ARCH_BOARD_PX4FMU_V1
|
#endif // CONFIG_ARCH_BOARD_PX4FMU_V1
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -426,32 +418,7 @@ void AP_BoardConfig::px4_start_common_sensors(void)
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // CONFIG_HAL_BOARD
|
||||||
/*
|
|
||||||
setup optional sensors
|
|
||||||
*/
|
|
||||||
void AP_BoardConfig::px4_start_optional_sensors(void)
|
|
||||||
{
|
|
||||||
if (px4_start_driver(ll40ls_main, "ll40ls", "-X start")) {
|
|
||||||
printf("Found external ll40ls sensor\n");
|
|
||||||
}
|
|
||||||
if (px4_start_driver(ll40ls_main, "ll40ls", "-I start")) {
|
|
||||||
printf("Found internal ll40ls sensor\n");
|
|
||||||
}
|
|
||||||
if (px4_start_driver(trone_main, "trone", "start")) {
|
|
||||||
printf("Found trone sensor\n");
|
|
||||||
}
|
|
||||||
if (px4_start_driver(mb12xx_main, "mb12xx", "start")) {
|
|
||||||
printf("Found mb12xx sensor\n");
|
|
||||||
}
|
|
||||||
|
|
||||||
#if !defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
|
||||||
if (px4_start_driver(pwm_input_main, "pwm_input", "start")) {
|
|
||||||
printf("started pwm_input driver\n");
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||||
void AP_BoardConfig::vrx_start_brain51_sensors(void)
|
void AP_BoardConfig::vrx_start_brain51_sensors(void)
|
||||||
@ -556,31 +523,7 @@ void AP_BoardConfig::vrx_start_common_sensors(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // CONFIG_HAL_BOARD
|
||||||
/*
|
|
||||||
setup optional sensors
|
|
||||||
*/
|
|
||||||
void AP_BoardConfig::vrx_start_optional_sensors(void)
|
|
||||||
{
|
|
||||||
if (px4_start_driver(ll40ls_main, "ll40ls", "-X start")) {
|
|
||||||
printf("Found external ll40ls sensor\n");
|
|
||||||
}
|
|
||||||
if (px4_start_driver(ll40ls_main, "ll40ls", "-I start")) {
|
|
||||||
printf("Found internal ll40ls sensor\n");
|
|
||||||
}
|
|
||||||
|
|
||||||
if (px4_start_driver(trone_main, "trone", "start")) {
|
|
||||||
printf("Found trone sensor\n");
|
|
||||||
}
|
|
||||||
if (px4_start_driver(mb12xx_main, "mb12xx", "start")) {
|
|
||||||
printf("Found mb12xx sensor\n");
|
|
||||||
}
|
|
||||||
|
|
||||||
if (px4_start_driver(pwm_input_main, "pwm_input", "start")) {
|
|
||||||
printf("started pwm_input driver\n");
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
void AP_BoardConfig::px4_setup_drivers(void)
|
void AP_BoardConfig::px4_setup_drivers(void)
|
||||||
{
|
{
|
||||||
@ -623,8 +566,6 @@ void AP_BoardConfig::px4_setup_drivers(void)
|
|||||||
px4_start_fmuv2_sensors();
|
px4_start_fmuv2_sensors();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
px4_start_optional_sensors();
|
|
||||||
|
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||||
vrx_start_common_sensors();
|
vrx_start_common_sensors();
|
||||||
switch ((px4_board_type)px4.board_type.get()) {
|
switch ((px4_board_type)px4.board_type.get()) {
|
||||||
@ -655,8 +596,6 @@ void AP_BoardConfig::px4_setup_drivers(void)
|
|||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
vrx_start_optional_sensors();
|
|
||||||
|
|
||||||
#endif // HAL_BOARD_PX4
|
#endif // HAL_BOARD_PX4
|
||||||
|
|
||||||
px4_configured_board = (enum px4_board_type)px4.board_type.get();
|
px4_configured_board = (enum px4_board_type)px4.board_type.get();
|
||||||
@ -797,13 +736,6 @@ bool AP_BoardConfig::spi_check_register(const char *devname, uint8_t regnum, uin
|
|||||||
*/
|
*/
|
||||||
void AP_BoardConfig::px4_autodetect(void)
|
void AP_BoardConfig::px4_autodetect(void)
|
||||||
{
|
{
|
||||||
if (px4.board_type == PX4_BOARD_TEST_V1 ||
|
|
||||||
px4.board_type == PX4_BOARD_TEST_V2 ||
|
|
||||||
px4.board_type == PX4_BOARD_TEST_V3) {
|
|
||||||
// these were old test values
|
|
||||||
px4.board_type.set(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (px4.board_type != PX4_BOARD_AUTO) {
|
if (px4.board_type != PX4_BOARD_AUTO) {
|
||||||
// user has chosen a board type
|
// user has chosen a board type
|
||||||
return;
|
return;
|
||||||
|
Loading…
Reference in New Issue
Block a user