mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
ArduCopter: 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
1a084e5dcd
commit
e0639ac029
@ -1787,7 +1787,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, copter.gps);
|
||||
break;
|
||||
@ -1797,8 +1796,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
break;
|
||||
|
||||
#endif
|
||||
|
||||
#if PRECISION_LANDING == ENABLED
|
||||
case MAVLINK_MSG_ID_LANDING_TARGET:
|
||||
// configure or release parachute
|
||||
|
@ -4,18 +4,19 @@
|
||||
|
||||
#if CLI_ENABLED == ENABLED
|
||||
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||
#define WITH_ESC_CALIB
|
||||
#endif
|
||||
#define PWM_CALIB_MIN 1000
|
||||
#define PWM_CALIB_MAX 2000
|
||||
#define PWM_HIGHEST_MAX 2200
|
||||
#define PWM_LOWEST_MAX 1200
|
||||
#define PWM_HIGHEST_MIN 1800
|
||||
#define PWM_LOWEST_MIN 800
|
||||
|
||||
// Command/function table for the setup menu
|
||||
static const struct Menu::command setup_menu_commands[] = {
|
||||
{"reset", MENU_FUNC(setup_factory)},
|
||||
{"show", MENU_FUNC(setup_show)},
|
||||
{"set", MENU_FUNC(setup_set)},
|
||||
#ifdef WITH_ESC_CALIB
|
||||
{"esc_calib", MENU_FUNC(esc_calib)},
|
||||
#endif
|
||||
};
|
||||
|
||||
// Create the setup menu object.
|
||||
@ -156,14 +157,6 @@ int8_t Copter::setup_show(uint8_t argc, const Menu::arg *argv)
|
||||
return(0);
|
||||
}
|
||||
|
||||
#ifdef WITH_ESC_CALIB
|
||||
#define PWM_CALIB_MIN 1000
|
||||
#define PWM_CALIB_MAX 2000
|
||||
#define PWM_HIGHEST_MAX 2200
|
||||
#define PWM_LOWEST_MAX 1200
|
||||
#define PWM_HIGHEST_MIN 1800
|
||||
#define PWM_LOWEST_MIN 800
|
||||
|
||||
int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
||||
{
|
||||
|
||||
@ -299,7 +292,6 @@ int8_t Copter::esc_calib(uint8_t argc,const Menu::arg *argv)
|
||||
|
||||
return(0);
|
||||
}
|
||||
#endif // WITH_ESC_CALIB
|
||||
|
||||
|
||||
/***************************************************************************/
|
||||
|
Loading…
Reference in New Issue
Block a user