mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: remove check for AVR CPUs
Remove the checks for HAL_CPU_CLASS > HAL_CPU_CLASS_16 and HAL_CPU_CLASS >= HAL_CPU_CLASS_75. Corresponding dead code will be removed on separate commits.
This commit is contained in:
parent
e0639ac029
commit
c55c07eaf6
|
@ -162,9 +162,7 @@ void Plane::ahrs_update()
|
|||
|
||||
if (should_log(MASK_LOG_IMU)) {
|
||||
Log_Write_IMU();
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||
DataFlash.Log_Write_IMUDT(ins);
|
||||
#endif
|
||||
}
|
||||
|
||||
// calculate a scaled roll limit based on current pitch
|
||||
|
@ -267,10 +265,8 @@ void Plane::update_logging2(void)
|
|||
if (should_log(MASK_LOG_RC))
|
||||
Log_Write_RC();
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||
if (should_log(MASK_LOG_IMU))
|
||||
DataFlash.Log_Write_Vibration(ins);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
@ -330,9 +326,7 @@ void Plane::one_second_loop()
|
|||
Log_Write_Status();
|
||||
}
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
||||
#endif
|
||||
}
|
||||
|
||||
void Plane::log_perf_info()
|
||||
|
@ -342,10 +336,11 @@ void Plane::log_perf_info()
|
|||
(unsigned long)G_Dt_max,
|
||||
(unsigned long)G_Dt_min);
|
||||
}
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||
if (should_log(MASK_LOG_PM))
|
||||
|
||||
if (should_log(MASK_LOG_PM)) {
|
||||
Log_Write_Performance();
|
||||
#endif
|
||||
}
|
||||
|
||||
G_Dt_max = 0;
|
||||
G_Dt_min = 0;
|
||||
resetPerfData();
|
||||
|
|
|
@ -1854,7 +1854,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
}
|
||||
break;
|
||||
|
||||
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
|
||||
case MAVLINK_MSG_ID_SERIAL_CONTROL:
|
||||
handle_serial_control(msg, plane.gps);
|
||||
break;
|
||||
|
@ -1863,8 +1862,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
handle_gps_inject(msg, plane.gps);
|
||||
break;
|
||||
|
||||
#endif
|
||||
|
||||
case MAVLINK_MSG_ID_TERRAIN_DATA:
|
||||
case MAVLINK_MSG_ID_TERRAIN_CHECK:
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
|
|
|
@ -164,12 +164,10 @@ void Plane::Log_Write_Attitude(void)
|
|||
targets.z = 0; //Plane does not have the concept of navyaw. This is a placeholder.
|
||||
|
||||
DataFlash.Log_Write_Attitude(ahrs, targets);
|
||||
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
|
||||
DataFlash.Log_Write_PID(LOG_PIDR_MSG, rollController.get_pid_info());
|
||||
DataFlash.Log_Write_PID(LOG_PIDP_MSG, pitchController.get_pid_info());
|
||||
DataFlash.Log_Write_PID(LOG_PIDY_MSG, yawController.get_pid_info());
|
||||
DataFlash.Log_Write_PID(LOG_PIDS_MSG, steerController.get_pid_info());
|
||||
#endif
|
||||
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
#if OPTFLOW == ENABLED
|
||||
|
|
|
@ -63,11 +63,7 @@
|
|||
//
|
||||
|
||||
#ifndef FRSKY_TELEM_ENABLED
|
||||
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
|
||||
# define FRSKY_TELEM_ENABLED ENABLED
|
||||
#else
|
||||
# define FRSKY_TELEM_ENABLED DISABLED
|
||||
#endif
|
||||
#define FRSKY_TELEM_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -82,11 +78,7 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
|
||||
# define RANGEFINDER_ENABLED ENABLED
|
||||
#else
|
||||
# define RANGEFINDER_ENABLED DISABLED
|
||||
#endif
|
||||
#define RANGEFINDER_ENABLED ENABLED
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -248,11 +240,7 @@
|
|||
//
|
||||
// uses 7726 bytes of memory on 2560 chips (all options are enabled)
|
||||
#ifndef MOUNT
|
||||
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
|
||||
# define MOUNT ENABLED
|
||||
#else
|
||||
# define MOUNT DISABLED
|
||||
#endif
|
||||
#define MOUNT ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -393,11 +381,7 @@
|
|||
// use this to completely disable the CLI. We now default the CLI to
|
||||
// off on smaller boards.
|
||||
#ifndef CLI_ENABLED
|
||||
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
|
||||
# define CLI_ENABLED ENABLED
|
||||
#else
|
||||
# define CLI_ENABLED DISABLE
|
||||
#endif
|
||||
#define CLI_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
// use this to disable geo-fencing
|
||||
|
@ -426,31 +410,15 @@
|
|||
|
||||
// OBC Failsafe enable
|
||||
#ifndef OBC_FAILSAFE
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||
# define OBC_FAILSAFE ENABLED
|
||||
#else
|
||||
# define OBC_FAILSAFE DISABLED
|
||||
#endif
|
||||
#define OBC_FAILSAFE ENABLED
|
||||
#endif
|
||||
|
||||
#if OBC_FAILSAFE == ENABLED && HAL_CPU_CLASS < HAL_CPU_CLASS_75
|
||||
#define CLI_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75
|
||||
#define HIL_SUPPORT DISABLED
|
||||
#else
|
||||
#define HIL_SUPPORT ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Parachute release
|
||||
#ifndef PARACHUTE
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||
# define PARACHUTE ENABLED
|
||||
#else
|
||||
# define PARACHUTE DISABLED
|
||||
#endif
|
||||
#define PARACHUTE ENABLED
|
||||
#endif
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue