mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: added VRBRAIN #defines and #includes
This commit is contained in:
parent
9e31f032c2
commit
a111d174c1
@ -99,6 +99,7 @@ static AP_Vehicle::FixedWing aparm;
|
||||
#include <AP_HAL_FLYMAPLE.h>
|
||||
#include <AP_HAL_Linux.h>
|
||||
#include <AP_HAL_Empty.h>
|
||||
#include <AP_HAL_VRBRAIN.h>
|
||||
|
||||
AP_HAL::BetterStream* cliSerial;
|
||||
|
||||
@ -164,6 +165,8 @@ static DataFlash_File DataFlash("logs");
|
||||
static DataFlash_File DataFlash("/fs/microsd/APM/LOGS");
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
static DataFlash_File DataFlash("logs");
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
static DataFlash_File DataFlash("/fs/microsd/APM/LOGS");
|
||||
#else
|
||||
// no dataflash driver
|
||||
DataFlash_Empty DataFlash;
|
||||
@ -200,6 +203,8 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
|
||||
static AP_Baro_BMP085 barometer;
|
||||
#elif CONFIG_BARO == AP_BARO_PX4
|
||||
static AP_Baro_PX4 barometer;
|
||||
#elif CONFIG_BARO == AP_BARO_VRABRAIN
|
||||
static AP_Baro_VRBRAIN barometer;
|
||||
#elif CONFIG_BARO == AP_BARO_HIL
|
||||
static AP_Baro_HIL barometer;
|
||||
#elif CONFIG_BARO == AP_BARO_MS5611
|
||||
@ -216,6 +221,8 @@ static AP_Baro_HIL barometer;
|
||||
|
||||
#if CONFIG_COMPASS == AP_COMPASS_PX4
|
||||
static AP_Compass_PX4 compass;
|
||||
#elif CONFIG_COMPASS == AP_COMPASS_VRBRAIN
|
||||
static AP_Compass_VRBRAIN compass;
|
||||
#elif CONFIG_COMPASS == AP_COMPASS_HMC5843
|
||||
static AP_Compass_HMC5843 compass;
|
||||
#elif CONFIG_COMPASS == AP_COMPASS_HIL
|
||||
@ -232,6 +239,8 @@ AP_ADC_ADS7844 apm1_adc;
|
||||
AP_InertialSensor_MPU6000 ins;
|
||||
#elif CONFIG_INS_TYPE == CONFIG_INS_PX4
|
||||
AP_InertialSensor_PX4 ins;
|
||||
#elif CONFIG_INS_TYPE == CONFIG_INS_VRBRAIN
|
||||
AP_InertialSensor_VRBRAIN ins;
|
||||
#elif CONFIG_INS_TYPE == CONFIG_INS_HIL
|
||||
AP_InertialSensor_HIL ins;
|
||||
#elif CONFIG_INS_TYPE == CONFIG_INS_OILPAN
|
||||
|
@ -440,14 +440,14 @@ public:
|
||||
RC_Channel_aux rc_6;
|
||||
RC_Channel_aux rc_7;
|
||||
RC_Channel_aux rc_8;
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
RC_Channel_aux rc_9;
|
||||
#endif
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
RC_Channel_aux rc_10;
|
||||
RC_Channel_aux rc_11;
|
||||
#endif
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
RC_Channel_aux rc_12;
|
||||
RC_Channel_aux rc_13;
|
||||
RC_Channel_aux rc_14;
|
||||
@ -465,14 +465,14 @@ public:
|
||||
rc_6 (CH_6),
|
||||
rc_7 (CH_7),
|
||||
rc_8 (CH_8),
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
rc_9 (CH_9),
|
||||
#endif
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
rc_10 (CH_10),
|
||||
rc_11 (CH_11),
|
||||
#endif
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
rc_12 (CH_12),
|
||||
rc_13 (CH_13),
|
||||
rc_14 (CH_14),
|
||||
|
@ -862,13 +862,13 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||
GGROUP(rc_8, "RC8_", RC_Channel_aux),
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
// @Group: RC9_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||
GGROUP(rc_9, "RC9_", RC_Channel_aux),
|
||||
#endif
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
// @Group: RC10_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||
GGROUP(rc_10, "RC10_", RC_Channel_aux),
|
||||
@ -878,7 +878,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
GGROUP(rc_11, "RC11_", RC_Channel_aux),
|
||||
#endif
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
// @Group: RC12_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||
GGROUP(rc_12, "RC12_", RC_Channel_aux),
|
||||
|
@ -115,6 +115,11 @@
|
||||
# define CONFIG_INS_TYPE CONFIG_INS_L3G4200D
|
||||
# define CONFIG_BARO AP_BARO_BMP085
|
||||
# define CONFIG_COMPASS AP_COMPASS_HMC5843
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
# define CONFIG_INS_TYPE CONFIG_INS_VRBRAIN
|
||||
# define CONFIG_BARO AP_BARO_VRBRAIN
|
||||
# define CONFIG_COMPASS AP_COMPASS_VRBRAIN
|
||||
# define SERIAL0_BAUD 115200
|
||||
#endif
|
||||
|
||||
|
||||
|
@ -203,17 +203,20 @@ enum log_messages {
|
||||
#define CONFIG_INS_PX4 4
|
||||
#define CONFIG_INS_FLYMAPLE 5
|
||||
#define CONFIG_INS_L3G4200D 6
|
||||
#define CONFIG_INS_VRBRAIN 7
|
||||
|
||||
// barometer driver types
|
||||
#define AP_BARO_BMP085 1
|
||||
#define AP_BARO_MS5611 2
|
||||
#define AP_BARO_PX4 3
|
||||
#define AP_BARO_HIL 4
|
||||
#define AP_BARO_VRBRAIN 5
|
||||
|
||||
// compass driver types
|
||||
#define AP_COMPASS_HMC5843 1
|
||||
#define AP_COMPASS_PX4 2
|
||||
#define AP_COMPASS_HIL 3
|
||||
#define AP_COMPASS_VRBRAIN 4
|
||||
|
||||
// altitude control algorithms
|
||||
enum {
|
||||
|
@ -477,6 +477,9 @@ static void report_compass()
|
||||
case AP_COMPASS_TYPE_PX4:
|
||||
cliSerial->println_P(PSTR("PX4"));
|
||||
break;
|
||||
case AP_COMPASS_TYPE_VRBRAIN:
|
||||
cliSerial->println_P(PSTR("VRBRAIN"));
|
||||
break;
|
||||
default:
|
||||
cliSerial->println_P(PSTR("(unknown)"));
|
||||
break;
|
||||
|
@ -22,7 +22,7 @@ static int8_t test_xbee(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_eedump(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_modeswitch(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_logging(uint8_t argc, const Menu::arg *argv);
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
static int8_t test_shell(uint8_t argc, const Menu::arg *argv);
|
||||
#endif
|
||||
|
||||
@ -61,7 +61,7 @@ static const struct Menu::command test_menu_commands[] PROGMEM = {
|
||||
{"compass", test_mag},
|
||||
#endif
|
||||
{"logging", test_logging},
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
{"shell", test_shell},
|
||||
#endif
|
||||
|
||||
@ -362,7 +362,7 @@ test_logging(uint8_t argc, const Menu::arg *argv)
|
||||
return 0;
|
||||
}
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
/*
|
||||
* run a debug shell
|
||||
*/
|
||||
|
Loading…
Reference in New Issue
Block a user