Browse Source

Copter: added VRBRAIN board #includes and #defines

mission-4.1.18
Emile Castelnuovo 11 years ago committed by Andrew Tridgell
parent
commit
9e31f032c2
  1. 9
      ArduCopter/ArduCopter.pde
  2. 8
      ArduCopter/Parameters.h
  3. 4
      ArduCopter/Parameters.pde
  4. 8
      ArduCopter/config.h
  5. 2
      ArduCopter/defines.h
  6. 6
      ArduCopter/test.pde

9
ArduCopter/ArduCopter.pde

@ -89,6 +89,7 @@ @@ -89,6 +89,7 @@
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_PX4.h>
#include <AP_HAL_VRBRAIN.h>
#include <AP_HAL_FLYMAPLE.h>
#include <AP_HAL_Linux.h>
#include <AP_HAL_Empty.h>
@ -213,6 +214,8 @@ static DataFlash_File DataFlash("logs"); @@ -213,6 +214,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
static DataFlash_Empty DataFlash;
#endif
@ -261,6 +264,8 @@ static AP_InertialSensor_Oilpan ins(&adc); @@ -261,6 +264,8 @@ static AP_InertialSensor_Oilpan ins(&adc);
static AP_InertialSensor_HIL ins;
#elif CONFIG_IMU_TYPE == CONFIG_IMU_PX4
static AP_InertialSensor_PX4 ins;
#elif CONFIG_IMU_TYPE == CONFIG_IMU_VRBRAIN
static AP_InertialSensor_VRBRAIN ins;
#elif CONFIG_IMU_TYPE == CONFIG_IMU_FLYMAPLE
AP_InertialSensor_Flymaple ins;
#elif CONFIG_IMU_TYPE == CONFIG_IMU_L3G4200D
@ -278,6 +283,8 @@ static SITL sitl; @@ -278,6 +283,8 @@ static SITL sitl;
static AP_Baro_BMP085 barometer;
#elif CONFIG_BARO == AP_BARO_PX4
static AP_Baro_PX4 barometer;
#elif CONFIG_BARO == AP_BARO_VRBRAIN
static AP_Baro_VRBRAIN barometer;
#elif CONFIG_BARO == AP_BARO_MS5611
#if CONFIG_MS5611_SERIAL == AP_BARO_MS5611_SPI
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::spi);
@ -290,6 +297,8 @@ static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::i2c); @@ -290,6 +297,8 @@ static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::i2c);
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
static AP_Compass_PX4 compass;
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
static AP_Compass_VRBRAIN compass;
#else
static AP_Compass_HMC5843 compass;
#endif

8
ArduCopter/Parameters.h

@ -398,12 +398,12 @@ public: @@ -398,12 +398,12 @@ 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
RC_Channel_aux rc_10;
RC_Channel_aux rc_11;
#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;
@ -466,12 +466,12 @@ public: @@ -466,12 +466,12 @@ 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
rc_10 (CH_10),
rc_11 (CH_11),
#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),

4
ArduCopter/Parameters.pde

@ -467,7 +467,7 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -467,7 +467,7 @@ 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),
@ -480,7 +480,7 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -480,7 +480,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_11, "RC11_", RC_Channel_aux),
#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),

8
ArduCopter/config.h

@ -97,6 +97,13 @@ @@ -97,6 +97,13 @@
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define OPTFLOW DISABLED
# define MAIN_LOOP_RATE 400
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
# define CONFIG_IMU_TYPE CONFIG_IMU_VRBRAIN
# define CONFIG_BARO AP_BARO_VRBRAIN
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED
# define OPTFLOW DISABLED
# define MAIN_LOOP_RATE 400
#endif
#if MAIN_LOOP_RATE == 400
@ -182,6 +189,7 @@ @@ -182,6 +189,7 @@
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
# define LED_ON LOW
# define LED_OFF HIGH
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
#endif
//////////////////////////////////////////////////////////////////////////////

2
ArduCopter/defines.h

@ -307,10 +307,12 @@ enum FlipState { @@ -307,10 +307,12 @@ enum FlipState {
#define CONFIG_IMU_SITL 3
#define CONFIG_IMU_PX4 4
#define CONFIG_IMU_FLYMAPLE 5
#define CONFIG_IMU_VRBRAIN 6
#define AP_BARO_BMP085 1
#define AP_BARO_MS5611 2
#define AP_BARO_PX4 3
#define AP_BARO_VRBRAIN 4
#define AP_BARO_MS5611_SPI 1
#define AP_BARO_MS5611_I2C 2

6
ArduCopter/test.pde

@ -13,7 +13,7 @@ static int8_t test_motors(uint8_t argc, const Menu::arg *argv); @@ -13,7 +13,7 @@ static int8_t test_motors(uint8_t argc, const Menu::arg *argv);
static int8_t test_motorsync(uint8_t argc, const Menu::arg *argv);
static int8_t test_optflow(uint8_t argc, const Menu::arg *argv);
static int8_t test_relay(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
#if HIL_MODE == HIL_MODE_DISABLED
@ -34,7 +34,7 @@ const struct Menu::command test_menu_commands[] PROGMEM = { @@ -34,7 +34,7 @@ const struct Menu::command test_menu_commands[] PROGMEM = {
{"motorsync", test_motorsync},
{"optflow", test_optflow},
{"relay", test_relay},
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
{"shell", test_shell},
#endif
#if HIL_MODE == HIL_MODE_DISABLED
@ -403,7 +403,7 @@ static int8_t test_relay(uint8_t argc, const Menu::arg *argv) @@ -403,7 +403,7 @@ static int8_t test_relay(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
/*
* run a debug shell
*/

Loading…
Cancel
Save