mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: remove checks for HAL_BOARD_APM2 and HAL_BOARD_APM1
This commit is contained in:
parent
3e889b005f
commit
d1be74c87e
|
@ -1060,9 +1060,7 @@ const AP_Param::Info Plane::var_info[] = {
|
|||
// @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 || 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),
|
||||
|
@ -1070,9 +1068,7 @@ const AP_Param::Info Plane::var_info[] = {
|
|||
// @Group: RC11_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||
GGROUP(rc_11, "RC11_", RC_Channel_aux),
|
||||
#endif
|
||||
|
||||
#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),
|
||||
|
|
|
@ -502,12 +502,8 @@ public:
|
|||
RC_Channel_aux rc_8;
|
||||
#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 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
RC_Channel_aux rc_10;
|
||||
RC_Channel_aux rc_11;
|
||||
#endif
|
||||
#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;
|
||||
|
@ -527,12 +523,8 @@ public:
|
|||
rc_8 (CH_8),
|
||||
#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 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
rc_10 (CH_10),
|
||||
rc_11 (CH_11),
|
||||
#endif
|
||||
#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),
|
||||
|
|
|
@ -351,25 +351,7 @@
|
|||
# define LOGGING_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
#define DEFAULT_LOG_BITMASK \
|
||||
MASK_LOG_ATTITUDE_MED | \
|
||||
MASK_LOG_GPS | \
|
||||
MASK_LOG_PM | \
|
||||
MASK_LOG_NTUN | \
|
||||
MASK_LOG_CTUN | \
|
||||
MASK_LOG_MODE | \
|
||||
MASK_LOG_CMD | \
|
||||
MASK_LOG_COMPASS | \
|
||||
MASK_LOG_CURRENT | \
|
||||
MASK_LOG_TECS | \
|
||||
MASK_LOG_CAMERA | \
|
||||
MASK_LOG_RC
|
||||
#else
|
||||
// other systems have plenty of space for full logs
|
||||
#define DEFAULT_LOG_BITMASK 0xffff
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
|
|
@ -74,10 +74,6 @@ static void failsafe_check_static()
|
|||
plane.failsafe_check();
|
||||
}
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
AP_ADC_ADS7844 apm1_adc;
|
||||
#endif
|
||||
|
||||
void Plane::init_ardupilot()
|
||||
{
|
||||
// initialise serial port
|
||||
|
@ -170,10 +166,6 @@ void Plane::init_ardupilot()
|
|||
log_init();
|
||||
#endif
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
apm1_adc.Init(); // APM ADC library initialization
|
||||
#endif
|
||||
|
||||
// initialise airspeed sensor
|
||||
airspeed.init();
|
||||
|
||||
|
@ -617,18 +609,6 @@ void Plane::check_usb_mux(void)
|
|||
|
||||
// the user has switched to/from the telemetry port
|
||||
usb_connected = usb_check;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
// the APM2 has a MUX setup where the first serial port switches
|
||||
// between USB and a TTL serial connection. When on USB we use
|
||||
// SERIAL0_BAUD, but when connected as a TTL serial port we run it
|
||||
// at SERIAL1_BAUD.
|
||||
if (usb_connected) {
|
||||
serial_manager.set_console_baud(AP_SerialManager::SerialProtocol_Console, 0);
|
||||
} else {
|
||||
serial_manager.set_console_baud(AP_SerialManager::SerialProtocol_MAVLink, 0);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
@ -797,9 +777,6 @@ bool Plane::disarm_motors(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
/*
|
||||
having local millis() and micros() reduces code size a bit on AVR
|
||||
*/
|
||||
uint32_t Plane::millis(void) const
|
||||
{
|
||||
return hal.scheduler->millis();
|
||||
|
|
|
@ -20,9 +20,6 @@ static const struct Menu::command test_menu_commands[] = {
|
|||
|
||||
// Tests below here are for hardware sensors only present
|
||||
// when real sensors are attached or they are emulated
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
{"adc", MENU_FUNC(test_adc)},
|
||||
#endif
|
||||
{"gps", MENU_FUNC(test_gps)},
|
||||
{"ins", MENU_FUNC(test_ins)},
|
||||
{"airspeed", MENU_FUNC(test_airspeed)},
|
||||
|
@ -318,26 +315,6 @@ int8_t Plane::test_shell(uint8_t argc, const Menu::arg *argv)
|
|||
//-------------------------------------------------------------------------------------------
|
||||
// tests in this section are for real sensors or sensors that have been simulated
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
int8_t Plane::test_adc(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
print_hit_enter();
|
||||
apm1_adc.Init();
|
||||
hal.scheduler->delay(1000);
|
||||
cliSerial->printf("ADC\n");
|
||||
hal.scheduler->delay(1000);
|
||||
|
||||
while(1) {
|
||||
for (int8_t i=0; i<9; i++) cliSerial->printf("%.1f\t",apm1_adc.Ch(i));
|
||||
cliSerial->println();
|
||||
hal.scheduler->delay(100);
|
||||
if(cliSerial->available() > 0) {
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
int8_t Plane::test_gps(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
print_hit_enter();
|
||||
|
|
Loading…
Reference in New Issue