mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Plane: removed some old defines
This commit is contained in:
parent
c524a7c717
commit
5e1f5ffb7f
@ -79,12 +79,6 @@
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// use this to enable telemetry on UART2. This is used
|
|
||||||
// when you have setup the solder bridge on an APM2 to enable UART2
|
|
||||||
#ifndef TELEMETRY_UART2
|
|
||||||
# define TELEMETRY_UART2 DISABLED
|
|
||||||
#endif
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// main board differences
|
// main board differences
|
||||||
//
|
//
|
||||||
@ -359,9 +353,6 @@
|
|||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Altitude measurement and control.
|
// Altitude measurement and control.
|
||||||
//
|
//
|
||||||
#ifndef ALT_EST_GAIN
|
|
||||||
# define ALT_EST_GAIN 0.01
|
|
||||||
#endif
|
|
||||||
#ifndef ALTITUDE_MIX
|
#ifndef ALTITUDE_MIX
|
||||||
# define ALTITUDE_MIX 1
|
# define ALTITUDE_MIX 1
|
||||||
#endif
|
#endif
|
||||||
@ -401,24 +392,6 @@
|
|||||||
#define ALT_HOLD_FBW_CM ALT_HOLD_FBW*100
|
#define ALT_HOLD_FBW_CM ALT_HOLD_FBW*100
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/* The following parameters have no corresponding control implementation
|
|
||||||
* #ifndef THROTTLE_ALT_P
|
|
||||||
# define THROTTLE_ALT_P 0.32
|
|
||||||
##endif
|
|
||||||
##ifndef THROTTLE_ALT_I
|
|
||||||
# define THROTTLE_ALT_I 0.0
|
|
||||||
##endif
|
|
||||||
##ifndef THROTTLE_ALT_D
|
|
||||||
# define THROTTLE_ALT_D 0.0
|
|
||||||
##endif
|
|
||||||
##ifndef THROTTLE_ALT_INT_MAX
|
|
||||||
# define THROTTLE_ALT_INT_MAX 20
|
|
||||||
##endif
|
|
||||||
##define THROTTLE_ALT_INT_MAX_CM THROTTLE_ALT_INT_MAX*100
|
|
||||||
*/
|
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Servo Mapping
|
// Servo Mapping
|
||||||
//
|
//
|
||||||
@ -448,130 +421,11 @@
|
|||||||
#define PITCH_MAX_CENTIDEGREE PITCH_MAX * 100
|
#define PITCH_MAX_CENTIDEGREE PITCH_MAX * 100
|
||||||
#define PITCH_MIN_CENTIDEGREE PITCH_MIN * 100
|
#define PITCH_MIN_CENTIDEGREE PITCH_MIN * 100
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
|
||||||
// Attitude control gains
|
|
||||||
//
|
|
||||||
#ifndef SERVO_ROLL_P
|
|
||||||
# define SERVO_ROLL_P 0.4
|
|
||||||
#endif
|
|
||||||
#ifndef SERVO_ROLL_I
|
|
||||||
# define SERVO_ROLL_I 0.0
|
|
||||||
#endif
|
|
||||||
#ifndef SERVO_ROLL_D
|
|
||||||
# define SERVO_ROLL_D 0.0
|
|
||||||
#endif
|
|
||||||
#ifndef SERVO_ROLL_INT_MAX
|
|
||||||
# define SERVO_ROLL_INT_MAX 5
|
|
||||||
#endif
|
|
||||||
#define SERVO_ROLL_INT_MAX_CENTIDEGREE SERVO_ROLL_INT_MAX*100
|
|
||||||
#ifndef SERVO_PITCH_P
|
|
||||||
# define SERVO_PITCH_P 0.6
|
|
||||||
#endif
|
|
||||||
#ifndef SERVO_PITCH_I
|
|
||||||
# define SERVO_PITCH_I 0.0
|
|
||||||
#endif
|
|
||||||
#ifndef SERVO_PITCH_D
|
|
||||||
# define SERVO_PITCH_D 0.0
|
|
||||||
#endif
|
|
||||||
#ifndef SERVO_PITCH_INT_MAX
|
|
||||||
# define SERVO_PITCH_INT_MAX 5
|
|
||||||
#endif
|
|
||||||
#define SERVO_PITCH_INT_MAX_CENTIDEGREE SERVO_PITCH_INT_MAX*100
|
|
||||||
#ifndef PITCH_COMP
|
|
||||||
# define PITCH_COMP 0.2
|
|
||||||
#endif
|
|
||||||
#ifndef SERVO_YAW_P
|
|
||||||
# define SERVO_YAW_P 0.0
|
|
||||||
#endif
|
|
||||||
#ifndef SERVO_YAW_I
|
|
||||||
# define SERVO_YAW_I 0.0
|
|
||||||
#endif
|
|
||||||
#ifndef SERVO_YAW_D
|
|
||||||
# define SERVO_YAW_D 0.0
|
|
||||||
#endif
|
|
||||||
#ifndef SERVO_YAW_INT_MAX
|
|
||||||
# define SERVO_YAW_INT_MAX 0
|
|
||||||
#endif
|
|
||||||
#ifndef RUDDER_MIX
|
#ifndef RUDDER_MIX
|
||||||
# define RUDDER_MIX 0.5
|
# define RUDDER_MIX 0.5
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
|
||||||
// Navigation control gains
|
|
||||||
//
|
|
||||||
#ifndef NAV_ROLL_P
|
|
||||||
# define NAV_ROLL_P 0.7
|
|
||||||
#endif
|
|
||||||
#ifndef NAV_ROLL_I
|
|
||||||
# define NAV_ROLL_I 0.02
|
|
||||||
#endif
|
|
||||||
#ifndef NAV_ROLL_D
|
|
||||||
# define NAV_ROLL_D 0.1
|
|
||||||
#endif
|
|
||||||
#ifndef NAV_ROLL_INT_MAX
|
|
||||||
# define NAV_ROLL_INT_MAX 5
|
|
||||||
#endif
|
|
||||||
#define NAV_ROLL_INT_MAX_CENTIDEGREE NAV_ROLL_INT_MAX*100
|
|
||||||
#ifndef NAV_PITCH_ASP_P
|
|
||||||
# define NAV_PITCH_ASP_P 0.65
|
|
||||||
#endif
|
|
||||||
#ifndef NAV_PITCH_ASP_I
|
|
||||||
# define NAV_PITCH_ASP_I 0.1
|
|
||||||
#endif
|
|
||||||
#ifndef NAV_PITCH_ASP_D
|
|
||||||
# define NAV_PITCH_ASP_D 0.0
|
|
||||||
#endif
|
|
||||||
#ifndef NAV_PITCH_ASP_INT_MAX
|
|
||||||
# define NAV_PITCH_ASP_INT_MAX 5
|
|
||||||
#endif
|
|
||||||
#define NAV_PITCH_ASP_INT_MAX_CMSEC NAV_PITCH_ASP_INT_MAX*100
|
|
||||||
#ifndef NAV_PITCH_ALT_P
|
|
||||||
# define NAV_PITCH_ALT_P 0.65
|
|
||||||
#endif
|
|
||||||
#ifndef NAV_PITCH_ALT_I
|
|
||||||
# define NAV_PITCH_ALT_I 0.1
|
|
||||||
#endif
|
|
||||||
#ifndef NAV_PITCH_ALT_D
|
|
||||||
# define NAV_PITCH_ALT_D 0.0
|
|
||||||
#endif
|
|
||||||
#ifndef NAV_PITCH_ALT_INT_MAX
|
|
||||||
# define NAV_PITCH_ALT_INT_MAX 5
|
|
||||||
#endif
|
|
||||||
#define NAV_PITCH_ALT_INT_MAX_CM NAV_PITCH_ALT_INT_MAX*100
|
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
|
||||||
// Energy/Altitude control gains
|
|
||||||
//
|
|
||||||
#ifndef THROTTLE_TE_P
|
|
||||||
# define THROTTLE_TE_P 0.50
|
|
||||||
#endif
|
|
||||||
#ifndef THROTTLE_TE_I
|
|
||||||
# define THROTTLE_TE_I 0.0
|
|
||||||
#endif
|
|
||||||
#ifndef THROTTLE_TE_D
|
|
||||||
# define THROTTLE_TE_D 0.0
|
|
||||||
#endif
|
|
||||||
#ifndef THROTTLE_TE_INT_MAX
|
|
||||||
# define THROTTLE_TE_INT_MAX 20
|
|
||||||
#endif
|
|
||||||
#ifndef PITCH_TARGET
|
|
||||||
# define PITCH_TARGET 0
|
|
||||||
#endif
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
|
||||||
// Crosstrack compensation
|
|
||||||
//
|
|
||||||
#ifndef XTRACK_GAIN
|
|
||||||
# define XTRACK_GAIN 1 // deg/m
|
|
||||||
#endif
|
|
||||||
#ifndef XTRACK_ENTRY_ANGLE
|
|
||||||
# define XTRACK_ENTRY_ANGLE 30 // deg
|
|
||||||
#endif
|
|
||||||
# define XTRACK_GAIN_SCALED XTRACK_GAIN*100
|
|
||||||
# define XTRACK_ENTRY_ANGLE_CENTIDEGREE XTRACK_ENTRY_ANGLE*100
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// DEBUGGING
|
// DEBUGGING
|
||||||
|
Loading…
Reference in New Issue
Block a user