mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
Rover: added VRBRAIN #defines and #includes
This commit is contained in:
parent
a111d174c1
commit
c5620dfd39
@ -100,6 +100,7 @@
|
|||||||
#include <AP_HAL_AVR.h>
|
#include <AP_HAL_AVR.h>
|
||||||
#include <AP_HAL_AVR_SITL.h>
|
#include <AP_HAL_AVR_SITL.h>
|
||||||
#include <AP_HAL_PX4.h>
|
#include <AP_HAL_PX4.h>
|
||||||
|
#include <AP_HAL_VRBRAIN.h>
|
||||||
#include <AP_HAL_FLYMAPLE.h>
|
#include <AP_HAL_FLYMAPLE.h>
|
||||||
#include <AP_HAL_Linux.h>
|
#include <AP_HAL_Linux.h>
|
||||||
#include <AP_HAL_Empty.h>
|
#include <AP_HAL_Empty.h>
|
||||||
@ -175,6 +176,8 @@ static DataFlash_File DataFlash("logs");
|
|||||||
static DataFlash_File DataFlash("/fs/microsd/APM/LOGS");
|
static DataFlash_File DataFlash("/fs/microsd/APM/LOGS");
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
static DataFlash_File DataFlash("logs");
|
static DataFlash_File DataFlash("logs");
|
||||||
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||||
|
static DataFlash_File DataFlash("/fs/microsd/APM/LOGS");
|
||||||
#else
|
#else
|
||||||
DataFlash_Empty DataFlash;
|
DataFlash_Empty DataFlash;
|
||||||
#endif
|
#endif
|
||||||
@ -206,6 +209,8 @@ static AP_ADC_ADS7844 adc;
|
|||||||
|
|
||||||
#if CONFIG_COMPASS == AP_COMPASS_PX4
|
#if CONFIG_COMPASS == AP_COMPASS_PX4
|
||||||
static AP_Compass_PX4 compass;
|
static AP_Compass_PX4 compass;
|
||||||
|
#elif CONFIG_COMPASS == AP_COMPASS_VRBRAIN
|
||||||
|
static AP_Compass_VRBRAIN compass;
|
||||||
#elif CONFIG_COMPASS == AP_COMPASS_HMC5843
|
#elif CONFIG_COMPASS == AP_COMPASS_HMC5843
|
||||||
static AP_Compass_HMC5843 compass;
|
static AP_Compass_HMC5843 compass;
|
||||||
#elif CONFIG_COMPASS == AP_COMPASS_HIL
|
#elif CONFIG_COMPASS == AP_COMPASS_HIL
|
||||||
@ -218,6 +223,8 @@ static AP_Compass_HIL compass;
|
|||||||
AP_InertialSensor_MPU6000 ins;
|
AP_InertialSensor_MPU6000 ins;
|
||||||
#elif CONFIG_INS_TYPE == CONFIG_INS_PX4
|
#elif CONFIG_INS_TYPE == CONFIG_INS_PX4
|
||||||
AP_InertialSensor_PX4 ins;
|
AP_InertialSensor_PX4 ins;
|
||||||
|
#elif CONFIG_INS_TYPE == CONFIG_INS_VRBRAIN
|
||||||
|
AP_InertialSensor_VRBRAIN ins;
|
||||||
#elif CONFIG_INS_TYPE == CONFIG_INS_HIL
|
#elif CONFIG_INS_TYPE == CONFIG_INS_HIL
|
||||||
AP_InertialSensor_HIL ins;
|
AP_InertialSensor_HIL ins;
|
||||||
#elif CONFIG_INS_TYPE == CONFIG_INS_FLYMAPLE
|
#elif CONFIG_INS_TYPE == CONFIG_INS_FLYMAPLE
|
||||||
@ -235,6 +242,8 @@ AP_InertialSensor_Oilpan ins( &adc );
|
|||||||
static AP_Baro_BMP085 barometer;
|
static AP_Baro_BMP085 barometer;
|
||||||
#elif CONFIG_BARO == AP_BARO_PX4
|
#elif CONFIG_BARO == AP_BARO_PX4
|
||||||
static AP_Baro_PX4 barometer;
|
static AP_Baro_PX4 barometer;
|
||||||
|
#elif CONFIG_BARO == AP_BARO_VRBRAIN
|
||||||
|
static AP_Baro_VRBRAIN barometer;
|
||||||
#elif CONFIG_BARO == AP_BARO_HIL
|
#elif CONFIG_BARO == AP_BARO_HIL
|
||||||
static AP_Baro_HIL barometer;
|
static AP_Baro_HIL barometer;
|
||||||
#elif CONFIG_BARO == AP_BARO_MS5611
|
#elif CONFIG_BARO == AP_BARO_MS5611
|
||||||
|
@ -236,14 +236,14 @@ public:
|
|||||||
RC_Channel_aux rc_6;
|
RC_Channel_aux rc_6;
|
||||||
RC_Channel_aux rc_7;
|
RC_Channel_aux rc_7;
|
||||||
RC_Channel_aux rc_8;
|
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;
|
RC_Channel_aux rc_9;
|
||||||
#endif
|
#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_10;
|
||||||
RC_Channel_aux rc_11;
|
RC_Channel_aux rc_11;
|
||||||
#endif
|
#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_12;
|
||||||
RC_Channel_aux rc_13;
|
RC_Channel_aux rc_13;
|
||||||
RC_Channel_aux rc_14;
|
RC_Channel_aux rc_14;
|
||||||
@ -301,14 +301,14 @@ public:
|
|||||||
rc_6(CH_6),
|
rc_6(CH_6),
|
||||||
rc_7(CH_7),
|
rc_7(CH_7),
|
||||||
rc_8(CH_8),
|
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),
|
rc_9 (CH_9),
|
||||||
#endif
|
#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_10 (CH_10),
|
||||||
rc_11 (CH_11),
|
rc_11 (CH_11),
|
||||||
#endif
|
#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_12 (CH_12),
|
||||||
rc_13 (CH_13),
|
rc_13 (CH_13),
|
||||||
rc_14 (CH_14),
|
rc_14 (CH_14),
|
||||||
|
@ -211,13 +211,13 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||||
GGROUP(rc_8, "RC8_", RC_Channel_aux),
|
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_
|
// @Group: RC9_
|
||||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||||
GGROUP(rc_9, "RC9_", RC_Channel_aux),
|
GGROUP(rc_9, "RC9_", RC_Channel_aux),
|
||||||
#endif
|
#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_
|
// @Group: RC10_
|
||||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||||
GGROUP(rc_10, "RC10_", RC_Channel_aux),
|
GGROUP(rc_10, "RC10_", RC_Channel_aux),
|
||||||
@ -227,7 +227,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
GGROUP(rc_11, "RC11_", RC_Channel_aux),
|
GGROUP(rc_11, "RC11_", RC_Channel_aux),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||||
// @Group: RC12_
|
// @Group: RC12_
|
||||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||||
GGROUP(rc_12, "RC12_", RC_Channel_aux),
|
GGROUP(rc_12, "RC12_", RC_Channel_aux),
|
||||||
|
@ -98,6 +98,12 @@
|
|||||||
# define CONFIG_BARO AP_BARO_BMP085
|
# define CONFIG_BARO AP_BARO_BMP085
|
||||||
# define BATTERY_PIN_1 -1
|
# define BATTERY_PIN_1 -1
|
||||||
# define CURRENT_PIN_1 -1
|
# define CURRENT_PIN_1 -1
|
||||||
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||||
|
# define CONFIG_INS_TYPE CONFIG_INS_VRBRAIN
|
||||||
|
# define CONFIG_COMPASS AP_COMPASS_VRBRAIN
|
||||||
|
# define CONFIG_BARO AP_BARO_VRBRAIN
|
||||||
|
# define BATTERY_PIN_1 -1
|
||||||
|
# define CURRENT_PIN_1 -1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -148,16 +148,19 @@ enum mode {
|
|||||||
#define CONFIG_INS_PX4 4
|
#define CONFIG_INS_PX4 4
|
||||||
#define CONFIG_INS_FLYMAPLE 5
|
#define CONFIG_INS_FLYMAPLE 5
|
||||||
#define CONFIG_INS_L3G4200D 6
|
#define CONFIG_INS_L3G4200D 6
|
||||||
|
#define CONFIG_INS_VRBRAIN 7
|
||||||
|
|
||||||
// barometer driver types
|
// barometer driver types
|
||||||
#define AP_BARO_BMP085 1
|
#define AP_BARO_BMP085 1
|
||||||
#define AP_BARO_MS5611 2
|
#define AP_BARO_MS5611 2
|
||||||
#define AP_BARO_PX4 3
|
#define AP_BARO_PX4 3
|
||||||
#define AP_BARO_HIL 4
|
#define AP_BARO_HIL 4
|
||||||
|
#define AP_BARO_VRBRAIN 5
|
||||||
|
|
||||||
// compass driver types
|
// compass driver types
|
||||||
#define AP_COMPASS_HMC5843 1
|
#define AP_COMPASS_HMC5843 1
|
||||||
#define AP_COMPASS_PX4 2
|
#define AP_COMPASS_PX4 2
|
||||||
#define AP_COMPASS_HIL 3
|
#define AP_COMPASS_HIL 3
|
||||||
|
#define AP_COMPASS_VRBRAIN 4
|
||||||
|
|
||||||
#endif // _DEFINES_H
|
#endif // _DEFINES_H
|
||||||
|
@ -16,7 +16,7 @@ static int8_t test_sonar(uint8_t argc, const Menu::arg *argv);
|
|||||||
static int8_t test_mag(uint8_t argc, const Menu::arg *argv);
|
static int8_t test_mag(uint8_t argc, const Menu::arg *argv);
|
||||||
static int8_t test_modeswitch(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);
|
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);
|
static int8_t test_shell(uint8_t argc, const Menu::arg *argv);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -43,7 +43,7 @@ static const struct Menu::command test_menu_commands[] PROGMEM = {
|
|||||||
{"sonartest", test_sonar},
|
{"sonartest", test_sonar},
|
||||||
{"compass", test_mag},
|
{"compass", test_mag},
|
||||||
{"logging", test_logging},
|
{"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},
|
{"shell", test_shell},
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
@ -519,7 +519,7 @@ test_sonar(uint8_t argc, const Menu::arg *argv)
|
|||||||
return (0);
|
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
|
* run a debug shell
|
||||||
*/
|
*/
|
||||||
|
Loading…
Reference in New Issue
Block a user