APMrover2: 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
cb8ae444d1
commit
1a084e5dcd
@ -1321,7 +1321,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, rover.gps);
|
||||
break;
|
||||
@ -1330,8 +1329,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
handle_gps_inject(msg, rover.gps);
|
||||
break;
|
||||
|
||||
#endif
|
||||
|
||||
case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST:
|
||||
rover.gcs[chan-MAVLINK_COMM_0].send_autopilot_version(FIRMWARE_VERSION);
|
||||
break;
|
||||
|
@ -291,10 +291,7 @@ void Rover::Log_Write_Attitude()
|
||||
#endif
|
||||
DataFlash.Log_Write_POS(ahrs);
|
||||
|
||||
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
|
||||
DataFlash.Log_Write_PID(LOG_PIDY_MSG, steerController.get_pid_info());
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
struct PACKED log_Sonar {
|
||||
|
@ -284,11 +284,7 @@
|
||||
|
||||
// use this to completely disable the CLI
|
||||
#ifndef CLI_ENABLED
|
||||
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
|
||||
# define CLI_ENABLED ENABLED
|
||||
#else
|
||||
# define CLI_ENABLED DISABLED
|
||||
#endif
|
||||
#define CLI_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
// if RESET_SWITCH_CH is not zero, then this is the PWM value on
|
||||
|
Loading…
Reference in New Issue
Block a user