ArduCopter: remove unused rc_override variables to save 21 bytes

This commit is contained in:
rmackay9 2012-12-17 17:04:51 +09:00 committed by Andrew Tridgell
parent 396024e802
commit e6519330f4
2 changed files with 0 additions and 18 deletions

View File

@ -423,17 +423,6 @@ MOTOR_CLASS motors(CONFIG_HAL_BOARD, &g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, &g.rc_7
MOTOR_CLASS motors(CONFIG_HAL_BOARD, &g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4);
#endif
////////////////////////////////////////////////////////////////////////////////
// Mavlink/HIL control
////////////////////////////////////////////////////////////////////////////////
// Used to track the GCS based control input
// Allow override of RC channel values for HIL
static int16_t rc_override[8] = {0,0,0,0,0,0,0,0};
// Status flag that tracks whether we are under GCS control
static bool rc_override_active = false;
// Status flag that tracks whether we are under GCS control
static uint32_t rc_override_fs_timer;
////////////////////////////////////////////////////////////////////////////////
// PIDs
////////////////////////////////////////////////////////////////////////////////

View File

@ -1083,13 +1083,6 @@
# define USE_CURRENT_ALT FALSE
#endif
//////////////////////////////////////////////////////////////////////////////
// RC override
//
#ifndef ALLOW_RC_OVERRIDE
# define ALLOW_RC_OVERRIDE DISABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// AP_Limits Defaults
//