mirror of https://github.com/ArduPilot/ardupilot
Copter: fix to allow building HIL_MODE_SENSORS
This commit is contained in:
parent
ac10e7ea26
commit
597a4b912a
|
@ -8,7 +8,7 @@
|
|||
// valid! You should switch to using a HAL_BOARD flag in your local config.mk.
|
||||
|
||||
//#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
|
||||
//#define HIL_MODE HIL_MODE_ATTITUDE
|
||||
//#define HIL_MODE HIL_MODE_SENSORS
|
||||
//#define DMP_ENABLED ENABLED
|
||||
//#define SECONDARY_DMP_ENABLED ENABLED // allows running DMP in parallel with DCM for testing purposes
|
||||
|
||||
|
|
|
@ -229,12 +229,6 @@ AP_Compass_HMC5843 compass;
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#if OPTFLOW == ENABLED
|
||||
AP_OpticalFlow_ADNS3080 optflow;
|
||||
#else
|
||||
AP_OpticalFlow optflow;
|
||||
#endif
|
||||
|
||||
// real GPS selection
|
||||
#if GPS_PROTOCOL == GPS_PROTOCOL_AUTO
|
||||
AP_GPS_Auto g_gps_driver(&g_gps);
|
||||
|
@ -292,19 +286,20 @@ AP_GPS_HIL g_gps_driver;
|
|||
AP_Compass_HIL compass; // never used
|
||||
AP_Baro_BMP085_HIL barometer;
|
||||
|
||||
#if OPTFLOW == ENABLED
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
AP_OpticalFlow_ADNS3080 optflow;
|
||||
#else
|
||||
AP_OpticalFlow_ADNS3080 optflow;
|
||||
#endif // CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
#endif // OPTFLOW == ENABLED
|
||||
|
||||
static int32_t gps_base_alt;
|
||||
#else
|
||||
#error Unrecognised HIL_MODE setting.
|
||||
#endif // HIL MODE
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Optical flow sensor
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
#if OPTFLOW == ENABLED
|
||||
AP_OpticalFlow_ADNS3080 optflow;
|
||||
#else
|
||||
AP_OpticalFlow optflow;
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// GCS selection
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
|
|
@ -1939,9 +1939,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
ins.set_accel_offsets(accels);
|
||||
|
||||
|
||||
#if HIL_MODE == HIL_MODE_ATTITUDE
|
||||
// set AHRS hil sensor
|
||||
ahrs.setHil(packet.roll,packet.pitch,packet.yaw,packet.rollspeed,
|
||||
packet.pitchspeed,packet.yawspeed);
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
|
|
@ -301,8 +301,7 @@
|
|||
# endif
|
||||
#else
|
||||
# warning Invalid value for CONFIG_SONAR_SOURCE, disabling sonar
|
||||
# undef SONAR_ENABLED
|
||||
# define SONAR_ENABLED DISABLED
|
||||
# define CONFIG_SONAR DISABLED
|
||||
#endif
|
||||
|
||||
#ifndef CONFIG_SONAR
|
||||
|
|
|
@ -43,11 +43,7 @@
|
|||
#define THROTTLE_LAND 8 // landing throttle controller
|
||||
|
||||
|
||||
// active altitude sensor
|
||||
// ----------------------
|
||||
#define SONAR 0
|
||||
#define BARO 1
|
||||
|
||||
// sonar - for use with CONFIG_SONAR_SOURCE
|
||||
#define SONAR_SOURCE_ADC 1
|
||||
#define SONAR_SOURCE_ANALOG_PIN 2
|
||||
|
||||
|
|
|
@ -60,9 +60,9 @@ apm_option("PITOT_ENABLED" TYPE BOOL
|
|||
DESCRIPTION "Enable pitot static system?"
|
||||
DEFAULT OFF)
|
||||
|
||||
apm_option("SONAR_ENABLED" TYPE BOOL
|
||||
apm_option("CONFIG_SONAR" TYPE BOOL
|
||||
DESCRIPTION "Enable sonar?"
|
||||
DEFAULT OFF)
|
||||
DEFAULT ON)
|
||||
|
||||
apm_option("AIRSPEED_RATIO" TYPE STRING ADVANCED
|
||||
DESCRIPTION "Airspeed ratio?"
|
||||
|
|
|
@ -24,7 +24,7 @@ static int8_t test_wp_nav(uint8_t argc, const Menu::arg *argv);
|
|||
static int8_t test_tuning(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_relay(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_wp(uint8_t argc, const Menu::arg *argv);
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE && HIL_MODE != HIL_MODE_SENSORS
|
||||
static int8_t test_baro(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_sonar(uint8_t argc, const Menu::arg *argv);
|
||||
#endif
|
||||
|
@ -75,7 +75,7 @@ const struct Menu::command test_menu_commands[] PROGMEM = {
|
|||
{"relay", test_relay},
|
||||
{"wp", test_wp},
|
||||
// {"toy", test_toy},
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE && HIL_MODE != HIL_MODE_SENSORS
|
||||
{"altitude", test_baro},
|
||||
{"sonar", test_sonar},
|
||||
#endif
|
||||
|
@ -794,7 +794,7 @@ test_wp(uint8_t argc, const Menu::arg *argv)
|
|||
* }
|
||||
*/
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE && HIL_MODE != HIL_MODE_SENSORS
|
||||
static int8_t
|
||||
test_baro(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
|
@ -902,13 +902,14 @@ test_mag(uint8_t argc, const Menu::arg *argv)
|
|||
* }
|
||||
* }*/
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE && HIL_MODE != HIL_MODE_SENSORS
|
||||
/*
|
||||
* test the sonar
|
||||
*/
|
||||
static int8_t
|
||||
test_sonar(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
#if CONFIG_SONAR == ENABLED
|
||||
if(g.sonar_enabled == false) {
|
||||
cliSerial->printf_P(PSTR("Sonar disabled\n"));
|
||||
return (0);
|
||||
|
@ -922,13 +923,12 @@ test_sonar(uint8_t argc, const Menu::arg *argv)
|
|||
delay(100);
|
||||
|
||||
cliSerial->printf_P(PSTR("Sonar: %d cm\n"), sonar->read());
|
||||
//cliSerial->printf_P(PSTR("Sonar, %d, %d\n"), sonar.read(), sonar.raw_value);
|
||||
|
||||
if(cliSerial->available() > 0) {
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
return (0);
|
||||
}
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue