Rover: remove unused definitions

This commit is contained in:
Randy Mackay 2017-08-17 10:10:22 +09:00
parent e116ec4eb0
commit bbb1329116
2 changed files with 0 additions and 42 deletions

View File

@ -56,13 +56,6 @@
#define CURRENT_PIN_1 -1
#endif
//////////////////////////////////////////////////////////////////////////////
// HIL_MODE OPTIONAL
#ifndef HIL_MODE
#define HIL_MODE HIL_MODE_DISABLED
#endif
#ifndef MAV_SYSTEM_ID
#define MAV_SYSTEM_ID 1
#endif
@ -81,10 +74,6 @@
#define CH7_OPTION CH7_SAVE_WP
#endif
#ifndef TUNING_OPTION
#define TUNING_OPTION TUN_NONE
#endif
//////////////////////////////////////////////////////////////////////////////
// MAGNETOMETER
#ifndef MAGNETOMETER
@ -124,14 +113,6 @@
#endif
//////////////////////////////////////////////////////////////////////////////
// THROTTLE_OUT
//
#ifndef THROTTE_OUT
#define THROTTLE_OUT ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// STARTUP BEHAVIOUR
@ -177,19 +158,6 @@
#define TURN_GAIN 5
#endif
//////////////////////////////////////////////////////////////////////////////
// Servo Mapping
//
#ifndef THROTTLE_MIN
#define THROTTLE_MIN 0 // percent
#endif
#ifndef THROTTLE_CRUISE
#define THROTTLE_CRUISE 45
#endif
#ifndef THROTTLE_MAX
#define THROTTLE_MAX 100
#endif
//////////////////////////////////////////////////////////////////////////////
// Dataflash logging control
//
@ -204,11 +172,6 @@
// Developer Items
//
// use this to enable servos in HIL mode
#ifndef HIL_SERVOS
#define HIL_SERVOS DISABLED
#endif
// if RESET_SWITCH_CH is not zero, then this is the PWM value on
// that channel where we reset the control mode to the current switch
// position (to for example return to switched mode after failsafe or

View File

@ -3,9 +3,6 @@
// Internal defines, don't edit and expect things to work
// -------------------------------------------------------
#define TRUE 1
#define FALSE 0
// Just so that it's completely clear...
#define ENABLED 1
#define DISABLED 0
@ -14,7 +11,6 @@
#define ENABLE ENABLED
#define DISABLE DISABLED
#define DEBUG 0
#define SERVO_MAX 4500 // This value represents 45 degrees and is just an arbitrary representation of servo max travel.
// CH 7 control
@ -59,7 +55,6 @@ enum mode {
#define TYPE_AIRSTART_MSG 0x00
#define TYPE_GROUNDSTART_MSG 0x01
#define MAX_NUM_LOGS 100
#define MASK_LOG_ATTITUDE_FAST (1<<0)
#define MASK_LOG_ATTITUDE_MED (1<<1)