mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: remove unused config
This commit is contained in:
parent
9ef3fd850f
commit
ea1158a9d5
@ -118,27 +118,13 @@
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
# define RC_FAST_SPEED 125
|
||||
# define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AHEAD
|
||||
# define RATE_INTEGRATOR_LEAK_RATE 0.02f
|
||||
# define RATE_ROLL_D 0
|
||||
# define RATE_PITCH_D 0
|
||||
# define HELI_PITCH_FF 0
|
||||
# define HELI_ROLL_FF 0
|
||||
# define HELI_YAW_FF 0
|
||||
# define STABILIZE_THR THROTTLE_MANUAL_HELI
|
||||
# define DRIFT_THR THROTTLE_MANUAL_HELI
|
||||
# define MPU6K_FILTER 10
|
||||
# define HELI_STAB_COLLECTIVE_MIN_DEFAULT 0
|
||||
# define HELI_STAB_COLLECTIVE_MAX_DEFAULT 1000
|
||||
# define THR_MIN_DEFAULT 0
|
||||
# define AUTOTUNE_ENABLED DISABLED
|
||||
|
||||
# ifndef HELI_CC_COMP
|
||||
#define HELI_CC_COMP DISABLED
|
||||
#endif
|
||||
# ifndef HELI_PIRO_COMP
|
||||
#define HELI_PIRO_COMP DISABLED
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
/////////////////////////////////////////////////////////////////////////////////
|
||||
@ -497,156 +483,59 @@
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Attitude Control
|
||||
// Flight mode definitions
|
||||
//
|
||||
|
||||
// Flight mode roll, pitch, yaw, throttle and navigation definitions
|
||||
|
||||
// Stabilize Mode
|
||||
#ifndef STABILIZE_YAW
|
||||
# define STABILIZE_YAW YAW_HOLD
|
||||
#endif
|
||||
#ifndef STABILIZE_RP
|
||||
# define STABILIZE_RP ROLL_PITCH_STABLE
|
||||
#endif
|
||||
#ifndef STABILIZE_THR
|
||||
# define STABILIZE_THR THROTTLE_MANUAL_TILT_COMPENSATED
|
||||
#endif
|
||||
|
||||
// Acro Mode
|
||||
#ifndef ACRO_YAW
|
||||
# define ACRO_YAW YAW_ACRO
|
||||
#ifndef ACRO_RP_P
|
||||
# define ACRO_RP_P 4.5f
|
||||
#endif
|
||||
|
||||
#ifndef ACRO_RP
|
||||
# define ACRO_RP ROLL_PITCH_ACRO
|
||||
#endif
|
||||
|
||||
#ifndef ACRO_THR
|
||||
# define ACRO_THR THROTTLE_MANUAL
|
||||
#ifndef ACRO_YAW_P
|
||||
# define ACRO_YAW_P 4.5f
|
||||
#endif
|
||||
|
||||
#ifndef ACRO_LEVEL_MAX_ANGLE
|
||||
# define ACRO_LEVEL_MAX_ANGLE 3000
|
||||
#endif
|
||||
|
||||
// Drift Mode
|
||||
#ifndef DRIFT_THR
|
||||
# define DRIFT_THR THROTTLE_MANUAL_TILT_COMPENSATED
|
||||
#ifndef ACRO_BALANCE_ROLL
|
||||
#define ACRO_BALANCE_ROLL 1.0f
|
||||
#endif
|
||||
|
||||
// Sport Mode
|
||||
#ifndef SPORT_YAW
|
||||
# define SPORT_YAW YAW_HOLD
|
||||
#ifndef ACRO_BALANCE_PITCH
|
||||
#define ACRO_BALANCE_PITCH 1.0f
|
||||
#endif
|
||||
|
||||
#ifndef SPORT_RP
|
||||
# define SPORT_RP ROLL_PITCH_SPORT
|
||||
// Stabilize (angle controller) gains
|
||||
#ifndef STABILIZE_ROLL_P
|
||||
# define STABILIZE_ROLL_P 4.5f
|
||||
#endif
|
||||
#ifndef STABILIZE_ROLL_I
|
||||
# define STABILIZE_ROLL_I 0.0f
|
||||
#endif
|
||||
#ifndef STABILIZE_ROLL_IMAX
|
||||
# define STABILIZE_ROLL_IMAX 0
|
||||
#endif
|
||||
|
||||
#ifndef SPORT_THR
|
||||
# define SPORT_THR THROTTLE_HOLD
|
||||
#ifndef STABILIZE_PITCH_P
|
||||
# define STABILIZE_PITCH_P 4.5f
|
||||
#endif
|
||||
#ifndef STABILIZE_PITCH_I
|
||||
# define STABILIZE_PITCH_I 0.0f
|
||||
#endif
|
||||
#ifndef STABILIZE_PITCH_IMAX
|
||||
# define STABILIZE_PITCH_IMAX 0
|
||||
#endif
|
||||
|
||||
// Alt Hold Mode
|
||||
#ifndef ALT_HOLD_YAW
|
||||
# define ALT_HOLD_YAW YAW_HOLD
|
||||
#ifndef STABILIZE_YAW_P
|
||||
# define STABILIZE_YAW_P 4.5f
|
||||
#endif
|
||||
|
||||
#ifndef ALT_HOLD_RP
|
||||
# define ALT_HOLD_RP ROLL_PITCH_STABLE
|
||||
#ifndef STABILIZE_YAW_I
|
||||
# define STABILIZE_YAW_I 0.0f
|
||||
#endif
|
||||
|
||||
#ifndef ALT_HOLD_THR
|
||||
# define ALT_HOLD_THR THROTTLE_HOLD
|
||||
#endif
|
||||
|
||||
// AUTO Mode
|
||||
// Note: Auto mode yaw behaviour is controlled by WP_YAW_BEHAVIOR parameter
|
||||
#ifndef WP_YAW_BEHAVIOR_DEFAULT
|
||||
# define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL
|
||||
#endif
|
||||
|
||||
#ifndef AUTO_RP
|
||||
# define AUTO_RP ROLL_PITCH_AUTO
|
||||
#endif
|
||||
|
||||
#ifndef AUTO_THR
|
||||
# define AUTO_THR THROTTLE_AUTO
|
||||
#endif
|
||||
|
||||
// CIRCLE Mode
|
||||
#ifndef CIRCLE_YAW
|
||||
# define CIRCLE_YAW YAW_CIRCLE
|
||||
#endif
|
||||
|
||||
#ifndef CIRCLE_RP
|
||||
# define CIRCLE_RP ROLL_PITCH_AUTO
|
||||
#endif
|
||||
|
||||
#ifndef CIRCLE_THR
|
||||
# define CIRCLE_THR THROTTLE_HOLD
|
||||
#endif
|
||||
|
||||
#ifndef CIRCLE_NAV
|
||||
# define CIRCLE_NAV NAV_CIRCLE
|
||||
#endif
|
||||
|
||||
#ifndef CIRCLE_RADIUS
|
||||
# define CIRCLE_RADIUS 10 // radius in meters for circle mode
|
||||
#endif
|
||||
|
||||
#ifndef CIRCLE_RATE
|
||||
# define CIRCLE_RATE 20.0f // degrees per second turn rate
|
||||
#endif
|
||||
|
||||
// Guided Mode
|
||||
// Note: Guided mode yaw behaviour is controlled by WP_YAW_BEHAVIOR parameter
|
||||
#ifndef GUIDED_RP
|
||||
# define GUIDED_RP ROLL_PITCH_AUTO
|
||||
#endif
|
||||
|
||||
#ifndef GUIDED_THR
|
||||
# define GUIDED_THR THROTTLE_AUTO
|
||||
#endif
|
||||
|
||||
#ifndef GUIDED_NAV
|
||||
# define GUIDED_NAV NAV_WP
|
||||
#endif
|
||||
|
||||
// LOITER Mode
|
||||
#ifndef LOITER_YAW
|
||||
# define LOITER_YAW YAW_HOLD
|
||||
#endif
|
||||
|
||||
#ifndef LOITER_RP
|
||||
# define LOITER_RP ROLL_PITCH_LOITER
|
||||
#endif
|
||||
|
||||
#ifndef LOITER_THR
|
||||
# define LOITER_THR THROTTLE_HOLD
|
||||
#endif
|
||||
|
||||
#ifndef LOITER_NAV
|
||||
# define LOITER_NAV NAV_LOITER
|
||||
#endif
|
||||
|
||||
// RTL Mode
|
||||
// Note: RTL Yaw behaviour is controlled by WP_YAW_BEHAVIOR parameter
|
||||
#ifndef RTL_RP
|
||||
# define RTL_RP ROLL_PITCH_AUTO
|
||||
#endif
|
||||
|
||||
#ifndef RTL_THR
|
||||
# define RTL_THR THROTTLE_AUTO
|
||||
#endif
|
||||
|
||||
#ifndef SUPER_SIMPLE
|
||||
# define SUPER_SIMPLE DISABLED
|
||||
#endif
|
||||
|
||||
#ifndef SUPER_SIMPLE_RADIUS
|
||||
# define SUPER_SIMPLE_RADIUS 1000
|
||||
#ifndef STABILIZE_YAW_IMAX
|
||||
# define STABILIZE_YAW_IMAX 0
|
||||
#endif
|
||||
|
||||
// RTL Mode
|
||||
@ -666,73 +555,23 @@
|
||||
# define RTL_LOITER_TIME 5000 // Time (in milliseconds) to loiter above home before begining final descent
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
// Optical Flow LOITER Mode
|
||||
#ifndef OF_LOITER_YAW
|
||||
# define OF_LOITER_YAW YAW_HOLD
|
||||
// AUTO Mode
|
||||
#ifndef WP_YAW_BEHAVIOR_DEFAULT
|
||||
# define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL
|
||||
#endif
|
||||
|
||||
#ifndef OF_LOITER_RP
|
||||
# define OF_LOITER_RP ROLL_PITCH_STABLE_OF
|
||||
#endif
|
||||
|
||||
#ifndef OF_LOITER_THR
|
||||
# define OF_LOITER_THR THROTTLE_HOLD
|
||||
#endif
|
||||
|
||||
#ifndef OF_LOITER_NAV
|
||||
# define OF_LOITER_NAV NAV_NONE
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Attitude Control
|
||||
//
|
||||
|
||||
// Acro mode gains
|
||||
#ifndef ACRO_RP_P
|
||||
# define ACRO_RP_P 4.5f
|
||||
#endif
|
||||
|
||||
#ifndef ACRO_YAW_P
|
||||
# define ACRO_YAW_P 4.5f
|
||||
#endif
|
||||
|
||||
// Stabilize (angle controller) gains
|
||||
#ifndef STABILIZE_ROLL_P
|
||||
# define STABILIZE_ROLL_P 4.5f
|
||||
#endif
|
||||
#ifndef STABILIZE_ROLL_I
|
||||
# define STABILIZE_ROLL_I 0.0f
|
||||
#endif
|
||||
#ifndef STABILIZE_ROLL_IMAX
|
||||
# define STABILIZE_ROLL_IMAX 0
|
||||
#endif
|
||||
|
||||
#ifndef STABILIZE_PITCH_P
|
||||
# define STABILIZE_PITCH_P 4.5f
|
||||
#endif
|
||||
#ifndef STABILIZE_PITCH_I
|
||||
# define STABILIZE_PITCH_I 0.0f
|
||||
#endif
|
||||
#ifndef STABILIZE_PITCH_IMAX
|
||||
# define STABILIZE_PITCH_IMAX 0
|
||||
#endif
|
||||
|
||||
#ifndef STABILIZE_YAW_P
|
||||
# define STABILIZE_YAW_P 4.5f // increase for more aggressive Yaw Hold, decrease if it's bouncy
|
||||
#endif
|
||||
#ifndef STABILIZE_YAW_I
|
||||
# define STABILIZE_YAW_I 0.0f
|
||||
#endif
|
||||
#ifndef STABILIZE_YAW_IMAX
|
||||
# define STABILIZE_YAW_IMAX 0
|
||||
#ifndef AUTO_YAW_SLEW_RATE
|
||||
# define AUTO_YAW_SLEW_RATE 60 // degrees/sec
|
||||
#endif
|
||||
|
||||
#ifndef YAW_LOOK_AHEAD_MIN_SPEED
|
||||
# define YAW_LOOK_AHEAD_MIN_SPEED 100 // minimum ground speed in cm/s required before copter is aimed at ground course
|
||||
#endif
|
||||
|
||||
// Super Simple mode
|
||||
#ifndef SUPER_SIMPLE_RADIUS
|
||||
# define SUPER_SIMPLE_RADIUS 1000
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Stabilize Rate Control
|
||||
@ -746,6 +585,10 @@
|
||||
#ifndef ANGLE_RATE_MAX
|
||||
# define ANGLE_RATE_MAX 18000 // default maximum rotation rate in roll/pitch axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Rate controller gains
|
||||
//
|
||||
#ifndef RATE_ROLL_P
|
||||
# define RATE_ROLL_P 0.150f
|
||||
#endif
|
||||
@ -785,31 +628,6 @@
|
||||
# define RATE_YAW_IMAX 800
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Rate controlled stabilized variables
|
||||
//
|
||||
|
||||
#ifndef MAX_ROLL_OVERSHOOT
|
||||
#define MAX_ROLL_OVERSHOOT 3000
|
||||
#endif
|
||||
|
||||
#ifndef MAX_PITCH_OVERSHOOT
|
||||
#define MAX_PITCH_OVERSHOOT 3000
|
||||
#endif
|
||||
|
||||
#ifndef MAX_YAW_OVERSHOOT
|
||||
#define MAX_YAW_OVERSHOOT 1000
|
||||
#endif
|
||||
|
||||
#ifndef ACRO_BALANCE_ROLL
|
||||
#define ACRO_BALANCE_ROLL 1.0f
|
||||
#endif
|
||||
|
||||
#ifndef ACRO_BALANCE_PITCH
|
||||
#define ACRO_BALANCE_PITCH 1.0f
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Loiter position control gains
|
||||
//
|
||||
@ -839,14 +657,6 @@
|
||||
# define LOITER_RATE_IMAX 400 // maximum acceleration from I term build-up in cm/s/s
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Autopilot rotate rate limits
|
||||
//
|
||||
#ifndef AUTO_YAW_SLEW_RATE
|
||||
# define AUTO_YAW_SLEW_RATE 60 // degrees/sec
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Throttle control gains
|
||||
//
|
||||
@ -869,10 +679,6 @@
|
||||
# define THROTTLE_IN_DEADBAND 100 // the throttle input channel's deadband in PWM
|
||||
#endif
|
||||
|
||||
#ifndef ALT_HOLD_TAKEOFF_JUMP
|
||||
# define ALT_HOLD_TAKEOFF_JUMP 20 // jump in altitude target when taking off in Loiter or AltHold flight modes
|
||||
#endif
|
||||
|
||||
#ifndef ALT_HOLD_P
|
||||
# define ALT_HOLD_P 1.0f
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user