AP_BoardConfig: defined and managed VRBRAIN board type and all functions for sensors startup

This commit is contained in:
LukeMike 2016-08-10 15:48:50 +02:00 committed by Andrew Tridgell
parent e6c8653302
commit 38150a5544
3 changed files with 220 additions and 7 deletions

View File

@ -43,9 +43,23 @@
#define BOARD_PWM_COUNT_DEFAULT 4
#define BOARD_SER1_RTSCTS_DEFAULT 2
#endif
#define BOARD_TYPE_DEFAULT PX4_BOARD_AUTO
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
# define BOARD_SAFETY_ENABLE_DEFAULT 0
# define BOARD_PWM_COUNT_DEFAULT 8
# if defined(CONFIG_ARCH_BOARD_VRBRAIN_V51)
# define BOARD_TYPE_DEFAULT VRX_BOARD_BRAIN51
# elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V52)
# define BOARD_TYPE_DEFAULT VRX_BOARD_BRAIN52
# elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V51)
# define BOARD_TYPE_DEFAULT VRX_BOARD_UBRAIN51
# elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52)
# define BOARD_TYPE_DEFAULT VRX_BOARD_UBRAIN52
# elif defined(CONFIG_ARCH_BOARD_VRCORE_V10)
# define BOARD_TYPE_DEFAULT VRX_BOARD_CORE10
# elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V54)
# define BOARD_TYPE_DEFAULT VRX_BOARD_BRAIN54
# endif
#endif
extern const AP_HAL::HAL& hal;
@ -129,13 +143,13 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
AP_GROUPINFO("IMU_TARGTEMP", 8, AP_BoardConfig, _imu_target_temperature, HAL_IMU_TEMP_DEFAULT),
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
// @Param: TYPE
// @DisplayName: Board type
// @Description: This allows selection of a PX4 board type. If set to zero then the board type is auto-detected
// @Values: 0:AUTO,1:PX4V1,2:Pixhawk,3:Pixhawk2,4:Pixracer,5:PixhawkMini,6:Pixhawk2Slim
// @Description: This allows selection of a PX4 or VRBRAIN board type. If set to zero then the board type is auto-detected (PX4)
// @Values: 0:AUTO,1:PX4V1,2:Pixhawk,3:Pixhawk2,4:Pixracer,5:PixhawkMini,6:Pixhawk2Slim,7:VRBrain 5.1,8:VRBrain 5.2,9:VR Micro Brain 5.1,10:VR Micro Brain 5.2,11:VRBrain Core 1.0,12:VRBrain 5.4
// @RebootRequired: True
AP_GROUPINFO("TYPE", 9, AP_BoardConfig, px4.board_type, PX4_BOARD_AUTO),
AP_GROUPINFO("TYPE", 9, AP_BoardConfig, px4.board_type, BOARD_TYPE_DEFAULT),
#endif
AP_GROUPEND

View File

@ -33,12 +33,13 @@ public:
static const struct AP_Param::GroupInfo var_info[];
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
// public method to start a driver
static bool px4_start_driver(main_fn_t main_function, const char *name, const char *arguments);
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
// valid types for BRD_TYPE
enum px4_board_type {
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
PX4_BOARD_AUTO = 0,
PX4_BOARD_PX4V1 = 1,
PX4_BOARD_PIXHAWK = 2,
@ -46,6 +47,15 @@ public:
PX4_BOARD_PIXRACER = 4,
PX4_BOARD_PHMINI = 5,
PX4_BOARD_PH2SLIM = 6,
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
VRX_BOARD_BRAIN51 = 7,
VRX_BOARD_BRAIN52 = 8,
VRX_BOARD_UBRAIN51 = 9,
VRX_BOARD_UBRAIN52 = 10,
VRX_BOARD_CORE10 = 11,
VRX_BOARD_BRAIN54 = 12,
#endif
};
#endif
@ -77,6 +87,7 @@ private:
void px4_setup_drivers(void);
void px4_sensor_error(const char *reason);
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
void px4_start_common_sensors(void);
void px4_start_fmuv1_sensors(void);
void px4_start_fmuv2_sensors(void);
@ -84,6 +95,19 @@ private:
void px4_start_pixhawk2slim_sensors(void);
void px4_start_phmini_sensors(void);
void px4_start_optional_sensors(void);
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
void vrx_start_common_sensors(void);
void vrx_start_brain51_sensors(void);
void vrx_start_brain52_sensors(void);
void vrx_start_ubrain51_sensors(void);
void vrx_start_ubrain52_sensors(void);
void vrx_start_core10_sensors(void);
void vrx_start_brain54_sensors(void);
void vrx_start_optional_sensors(void);
#endif
#endif // HAL_BOARD_PX4 || HAL_BOARD_VRBRAIN
// target temperarure for IMU in Celsius, or -1 to disable

View File

@ -260,6 +260,7 @@ bool AP_BoardConfig::px4_start_driver(main_fn_t main_function, const char *name,
return (status >> 8) == 0;
}
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
/*
setup sensors for PX4v2
*/
@ -500,7 +501,148 @@ void AP_BoardConfig::px4_start_optional_sensors(void)
}
#endif
}
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
void AP_BoardConfig::vrx_start_brain51_sensors(void)
{
#if defined(CONFIG_ARCH_BOARD_VRBRAIN_V51)
if (px4_start_driver(hmc5883_main, "hmc5883", "-C -R 12 -I start")) {
printf("HMC5883 Internal GPS started OK\n");
} else {
printf("HMC5883 Internal GPS start failed\n");
}
if (px4_start_driver(mpu6000_main, "mpu6000", "-R 12 start")) {
printf("MPU6000 Internal started OK\n");
} else {
px4_sensor_error("MPU6000 Internal start failed");
}
#endif
}
void AP_BoardConfig::vrx_start_brain52_sensors(void)
{
#if defined(CONFIG_ARCH_BOARD_VRBRAIN_V52)
if (px4_start_driver(hmc5883_main, "hmc5883", "-C -R 12 -I start")) {
printf("HMC5883 Internal GPS started OK\n");
} else {
printf("HMC5883 Internal GPS start failed\n");
}
if (px4_start_driver(mpu6000_main, "mpu6000", "-R 12 start")) {
printf("MPU6000 Internal started OK\n");
} else {
px4_sensor_error("MPU6000 Internal start failed");
}
#endif
}
void AP_BoardConfig::vrx_start_ubrain51_sensors(void)
{
#if defined(CONFIG_ARCH_BOARD_VRUBRAIN_V51)
if (px4_start_driver(mpu6000_main, "mpu6000", "-R 12 start")) {
printf("MPU6000 Internal started OK\n");
} else {
px4_sensor_error("MPU6000 Internal start failed");
}
#endif
}
void AP_BoardConfig::vrx_start_ubrain52_sensors(void)
{
#if defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52)
if (px4_start_driver(mpu6000_main, "mpu6000", "-R 12 start")) {
printf("MPU6000 Internal started OK\n");
} else {
px4_sensor_error("MPU6000 Internal start failed");
}
#endif
}
void AP_BoardConfig::vrx_start_core10_sensors(void)
{
#if defined(CONFIG_ARCH_BOARD_VRCORE_V10)
if (px4_start_driver(mpu9250_main, "mpu9250", "-R 4 start")) {
printf("MPU9250 Internal started OK\n");
} else {
px4_sensor_error("MPU9250 Internal start failed");
}
#endif
}
void AP_BoardConfig::vrx_start_brain54_sensors(void)
{
#if defined(CONFIG_ARCH_BOARD_VRBRAIN_V54)
if (px4_start_driver(hmc5883_main, "hmc5883", "-C -R 12 -I start")) {
printf("HMC5883 Internal GPS started OK\n");
} else {
printf("HMC5883 Internal GPS start failed\n");
}
if (px4_start_driver(mpu6000_main, "mpu6000", "-R 12 start")) {
printf("MPU6000 Internal started OK\n");
} else {
px4_sensor_error("MPU6000 Internal start failed");
}
#endif
}
/*
setup common sensors
*/
void AP_BoardConfig::vrx_start_common_sensors(void)
{
if (px4_start_driver(ms5611_main, "ms5611", "-s start")) {
printf("MS5611 Internal started OK\n");
} else {
px4_sensor_error("MS5611 Internal start failed");
}
if (px4_start_driver(hmc5883_main, "hmc5883", "-C -X start")) {
printf("HMC5883 External GPS started OK\n");
} else {
printf("HMC5883 External GPS start failed\n");
}
}
/*
setup optional sensors
*/
void AP_BoardConfig::vrx_start_optional_sensors(void)
{
if (px4_start_driver(ets_airspeed_main, "ets_airspeed", "start")) {
printf("Found ETS airspeed sensor\n");
} else if (px4_start_driver(ets_airspeed_main, "meas_airspeed", "start -b 2")) {
printf("Found ETS airspeed sensor (bus2)\n");
}
if (px4_start_driver(meas_airspeed_main, "meas_airspeed", "start")) {
printf("Found MEAS airspeed sensor\n");
} else if (px4_start_driver(meas_airspeed_main, "meas_airspeed", "start -b 2")) {
printf("Found MEAS airspeed sensor (bus2)\n");
}
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)
{
@ -524,9 +666,42 @@ void AP_BoardConfig::px4_setup_drivers(void)
}
px4_start_optional_sensors();
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
vrx_start_common_sensors();
switch ((px4_board_type)px4.board_type.get()) {
case VRX_BOARD_BRAIN51:
vrx_start_brain51_sensors();
break;
case VRX_BOARD_BRAIN52:
vrx_start_brain52_sensors();
break;
case VRX_BOARD_UBRAIN51:
vrx_start_ubrain51_sensors();
break;
case VRX_BOARD_UBRAIN52:
vrx_start_ubrain52_sensors();
break;
case VRX_BOARD_CORE10:
vrx_start_core10_sensors();
break;
case VRX_BOARD_BRAIN54:
vrx_start_brain54_sensors();
break;
default:
break;
}
vrx_start_optional_sensors();
#endif // HAL_BOARD_PX4
// delay for 1 second to give time for drivers to initialise
hal.scheduler->delay(1000);
#endif // HAL_BOARD_PX4
}
/*