mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: remove APM1, APM2 support
This commit is contained in:
parent
385558db4d
commit
088a49abbf
@ -221,11 +221,7 @@ static void gcs_send_text_fmt(const prog_char_t *fmt, ...);
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Dataflash
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
static DataFlash_APM2 DataFlash;
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
static DataFlash_APM1 DataFlash;
|
||||
#elif defined(HAL_BOARD_LOG_DIRECTORY)
|
||||
#if defined(HAL_BOARD_LOG_DIRECTORY)
|
||||
static DataFlash_File DataFlash(HAL_BOARD_LOG_DIRECTORY);
|
||||
#else
|
||||
static DataFlash_Empty DataFlash;
|
||||
@ -275,10 +271,6 @@ static AP_Compass_AK8963_MPU9250 compass;
|
||||
#error Unrecognized CONFIG_COMPASS setting
|
||||
#endif
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
AP_ADC_ADS7844 apm1_adc;
|
||||
#endif
|
||||
|
||||
AP_InertialSensor ins;
|
||||
|
||||
// Inertial Navigation EKF
|
||||
@ -634,7 +626,7 @@ static uint32_t rtl_loiter_start_time;
|
||||
// Used to exit the roll and pitch auto trim function
|
||||
static uint8_t auto_trim_counter;
|
||||
|
||||
// Reference to the relay object (APM1 -> PORTL 2) (APM2 -> PORTB 7)
|
||||
// Reference to the relay object
|
||||
static AP_Relay relay;
|
||||
|
||||
// handle repeated servo and relay events
|
||||
|
@ -40,18 +40,10 @@
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
#ifdef CONFIG_APM_HARDWARE
|
||||
#error CONFIG_APM_HARDWARE option is deprecated! use CONFIG_HAL_BOARD instead
|
||||
#endif
|
||||
|
||||
#ifndef CONFIG_HAL_BOARD
|
||||
#error CONFIG_HAL_BOARD must be defined to build ArduCopter
|
||||
#endif
|
||||
|
||||
#ifdef __AVR_ATmega1280__
|
||||
#error ATmega1280 is not supported
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// sensor types
|
||||
|
||||
@ -74,19 +66,14 @@
|
||||
|
||||
#define MAGNETOMETER ENABLED
|
||||
|
||||
// disable some features for APM1/APM2
|
||||
// low power cpus are not supported
|
||||
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75
|
||||
# define PARACHUTE DISABLED
|
||||
# define AC_RALLY DISABLED
|
||||
# define EPM_ENABLED DISABLED
|
||||
# define CLI_ENABLED DISABLED
|
||||
# define FRSKY_TELEM_ENABLED DISABLED
|
||||
# define NAV_GUIDED DISABLED
|
||||
# error ArduCopter ver3.3 and higher is not supported on APM1, APM2 boards
|
||||
#endif
|
||||
|
||||
|
||||
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
// low power CPUs (APM1, APM2 and SITL)
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
// slow loop rate in SITL, Linux
|
||||
# define MAIN_LOOP_RATE 100
|
||||
# define MAIN_LOOP_SECONDS 0.01
|
||||
# define MAIN_LOOP_MICROS 10000
|
||||
@ -151,17 +138,6 @@
|
||||
# define RATE_YAW_I 0.015f
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// ADC Enable - used to eliminate for systems which don't have ADC.
|
||||
//
|
||||
#ifndef CONFIG_ADC
|
||||
# if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
# define CONFIG_ADC ENABLED
|
||||
# else
|
||||
# define CONFIG_ADC DISABLED
|
||||
# endif
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// PWM control
|
||||
// default RC speed in Hz
|
||||
@ -169,20 +145,6 @@
|
||||
# define RC_FAST_SPEED 490
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////
|
||||
// LED and IO Pins
|
||||
//
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||
# define LED_ON LOW
|
||||
# define LED_OFF HIGH
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Barometer
|
||||
//
|
||||
@ -342,14 +304,8 @@
|
||||
#endif
|
||||
|
||||
// expected magnetic field strength. pre-arm checks will fail if 50% higher or lower than this value
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
#ifndef COMPASS_MAGFIELD_EXPECTED
|
||||
# define COMPASS_MAGFIELD_EXPECTED 330 // pre arm will fail if mag field > 544 or < 115
|
||||
#endif
|
||||
#else // PX4, SITL
|
||||
#ifndef COMPASS_MAGFIELD_EXPECTED
|
||||
#define COMPASS_MAGFIELD_EXPECTED 530 // pre arm will fail if mag field > 874 or < 185
|
||||
#endif
|
||||
#ifndef COMPASS_MAGFIELD_EXPECTED
|
||||
#define COMPASS_MAGFIELD_EXPECTED 530 // pre arm will fail if mag field > 874 or < 185
|
||||
#endif
|
||||
|
||||
// max compass offset length (i.e. sqrt(offs_x^2+offs_y^2+offs_Z^2))
|
||||
@ -357,7 +313,7 @@
|
||||
#ifndef COMPASS_OFFSETS_MAX
|
||||
# define COMPASS_OFFSETS_MAX 600 // PX4 onboard compass has high offsets
|
||||
#endif
|
||||
#else // APM1, APM2, SITL, FLYMAPLE, etc
|
||||
#else // SITL, FLYMAPLE, etc
|
||||
#ifndef COMPASS_OFFSETS_MAX
|
||||
# define COMPASS_OFFSETS_MAX 500
|
||||
#endif
|
||||
@ -734,19 +690,8 @@
|
||||
# define LOGGING_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
// APM1 & APM2 default logging
|
||||
# define DEFAULT_LOG_BITMASK \
|
||||
MASK_LOG_ATTITUDE_MED | \
|
||||
MASK_LOG_GPS | \
|
||||
MASK_LOG_PM | \
|
||||
MASK_LOG_CTUN | \
|
||||
MASK_LOG_NTUN | \
|
||||
MASK_LOG_RCIN | \
|
||||
MASK_LOG_CMD | \
|
||||
MASK_LOG_CURRENT
|
||||
#else
|
||||
// PX4, Pixhawk, FlyMaple default logging
|
||||
// Default logging bitmask
|
||||
#ifndef DEFAULT_LOG_BITMASK
|
||||
# define DEFAULT_LOG_BITMASK \
|
||||
MASK_LOG_ATTITUDE_MED | \
|
||||
MASK_LOG_GPS | \
|
||||
|
@ -89,14 +89,6 @@ static void init_ardupilot()
|
||||
"\n\nFree RAM: %u\n"),
|
||||
hal.util->available_memory());
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
/*
|
||||
run the timer a bit slower on APM2 to reduce the interrupt load
|
||||
on the CPU
|
||||
*/
|
||||
hal.scheduler->set_timer_speed(500);
|
||||
#endif
|
||||
|
||||
//
|
||||
// Report firmware version code expect on console (check of actual EEPROM format version is done in load_parameters function)
|
||||
//
|
||||
@ -139,12 +131,8 @@ static void init_ardupilot()
|
||||
// init the GCS connected to the console
|
||||
gcs[0].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_Console);
|
||||
|
||||
#if CONFIG_HAL_BOARD != HAL_BOARD_APM2
|
||||
// we have a 2nd serial port for telemetry on all boards except
|
||||
// APM2. We actually do have one on APM2 but it isn't necessary as
|
||||
// a MUX is used
|
||||
// init telemetry port
|
||||
gcs[1].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink1);
|
||||
#endif
|
||||
|
||||
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
||||
// setup serial port for telem2
|
||||
@ -185,11 +173,6 @@ static void init_ardupilot()
|
||||
*/
|
||||
hal.scheduler->register_timer_failsafe(failsafe_check, 1000);
|
||||
|
||||
#if CONFIG_ADC == ENABLED
|
||||
// begin filtering the ADC Gyros
|
||||
apm1_adc.Init(); // APM ADC library initialization
|
||||
#endif // CONFIG_ADC
|
||||
|
||||
// Do GPS init
|
||||
gps.init(&DataFlash, serial_manager);
|
||||
|
||||
@ -394,18 +377,6 @@ static void check_usb_mux(void)
|
||||
|
||||
// the user has switched to/from the telemetry port
|
||||
ap.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 (ap.usb_connected) {
|
||||
serial_manager.set_console_baud(AP_SerialManager::SerialProtocol_Console);
|
||||
} else {
|
||||
serial_manager.set_console_baud(AP_SerialManager::SerialProtocol_MAVLink1);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// frsky_telemetry_send - sends telemetry data using frsky telemetry
|
||||
|
Loading…
Reference in New Issue
Block a user