diff --git a/ArduSub/config.h b/ArduSub/config.h index b84e3bc359..dc50f33d20 100644 --- a/ArduSub/config.h +++ b/ArduSub/config.h @@ -151,19 +151,6 @@ # define FS_BATT_MAH_DEFAULT 0 // default battery capacity (in mah) below which failsafe will be triggered #endif -#ifndef BOARD_VOLTAGE_MIN -# define BOARD_VOLTAGE_MIN 4.3f // min board voltage in volts for pre-arm checks -#endif - -#ifndef BOARD_VOLTAGE_MAX -# define BOARD_VOLTAGE_MAX 5.8f // max board voltage in volts for pre-arm checks -#endif - -// prearm GPS hdop check -#ifndef GPS_HDOP_GOOD_DEFAULT -# define GPS_HDOP_GOOD_DEFAULT 140 // minimum hdop that represents a good position. used during pre-arm checks if fence is enabled -#endif - // GCS failsafe #ifndef FS_GCS # define FS_GCS DISABLED @@ -172,40 +159,11 @@ # define FS_GCS_TIMEOUT_MS 2500 // gcs failsafe triggers after 5 seconds with no GCS heartbeat #endif -// Radio failsafe while using RC_override -#ifndef FS_RADIO_RC_OVERRIDE_TIMEOUT_MS -# define FS_RADIO_RC_OVERRIDE_TIMEOUT_MS 1000 // RC Radio failsafe triggers after 1 second while using RC_override from ground station -#endif - -// Radio failsafe -#ifndef FS_RADIO_TIMEOUT_MS -#define FS_RADIO_TIMEOUT_MS 500 // RC Radio Failsafe triggers after 500 miliseconds with No RC Input -#endif - // missing terrain data failsafe #ifndef FS_TERRAIN_TIMEOUT_MS #define FS_TERRAIN_TIMEOUT_MS 1000 // 1 second of unhealthy rangefinder and/or missing terrain data will trigger failsafe #endif -#ifndef PREARM_DISPLAY_PERIOD -# define PREARM_DISPLAY_PERIOD 30 -#endif - -// pre-arm baro vs inertial nav max alt disparity -#ifndef PREARM_MAX_ALT_DISPARITY_CM -# define PREARM_MAX_ALT_DISPARITY_CM 100 // barometer and inertial nav altitude must be within this many centimeters -#endif - -// arming check's maximum acceptable accelerometer vector difference (in m/s/s) between primary and backup accelerometers -#ifndef PREARM_MAX_ACCEL_VECTOR_DIFF -#define PREARM_MAX_ACCEL_VECTOR_DIFF 0.70f // pre arm accel check will fail if primary and backup accelerometer vectors differ by 0.7m/s/s -#endif - -// arming check's maximum acceptable rotation rate difference (in rad/sec) between primary and backup gyros -#ifndef PREARM_MAX_GYRO_VECTOR_DIFF -#define PREARM_MAX_GYRO_VECTOR_DIFF 0.0873f // pre arm gyro check will fail if primary and backup gyro vectors differ by 0.0873 rad/sec (=5deg/sec) -#endif - ////////////////////////////////////////////////////////////////////////////// // EKF Failsafe #ifndef FS_EKF_ACTION_DEFAULT @@ -225,22 +183,6 @@ # define MAGNETOMETER ENABLED #endif -// expected magnetic field strength. pre-arm checks will fail if 50% higher or lower than this value -#ifndef COMPASS_MAGFIELD_EXPECTED -#define COMPASS_MAGFIELD_EXPECTED 530 // pre arm will fail if mag field > 874 or < 185 -#endif - -// max compass offset length (i.e. sqrt(offs_x^2+offs_y^2+offs_Z^2)) -#ifndef CONFIG_ARCH_BOARD_PX4FMU_V1 -#ifndef COMPASS_OFFSETS_MAX -# define COMPASS_OFFSETS_MAX 600 // PX4 onboard compass has high offsets -#endif -#else // SITL, etc -#ifndef COMPASS_OFFSETS_MAX -# define COMPASS_OFFSETS_MAX 500 -#endif -#endif - ////////////////////////////////////////////////////////////////////////////// // OPTICAL_FLOW #ifndef OPTFLOW @@ -288,14 +230,6 @@ # define FLIGHT_MODE_6 STABILIZE #endif - -////////////////////////////////////////////////////////////////////////////// -// Throttle Failsafe -// -#ifndef FS_THR_VALUE_DEFAULT -# define FS_THR_VALUE_DEFAULT 975 -#endif - ////////////////////////////////////////////////////////////////////////////// // CAMERA TRIGGER AND CONTROL // @@ -340,39 +274,6 @@ #define ACRO_EXPO_DEFAULT 0.3f #endif -// RTL Mode -#ifndef RTL_ALT_FINAL -# define RTL_ALT_FINAL 0 // the altitude the vehicle will move to as the final stage of Returning to Launch. -#endif - -#ifndef RTL_ALT -# define RTL_ALT 1500 // default alt to return to home in cm, 0 = Maintain current altitude -#endif - -#ifndef RTL_ALT_MIN -# define RTL_ALT_MIN 200 // min height above ground for RTL (i.e 2m) -#endif - -#ifndef RTL_CLIMB_MIN_DEFAULT -# define RTL_CLIMB_MIN_DEFAULT 0 // vehicle will always climb this many cm as first stage of RTL -#endif - -#ifndef RTL_ABS_MIN_CLIMB -# define RTL_ABS_MIN_CLIMB 250 // absolute minimum initial climb -#endif - -#ifndef RTL_CONE_SLOPE_DEFAULT -# define RTL_CONE_SLOPE_DEFAULT 3.0f // slope of RTL cone (height / distance). 0 = No cone -#endif - -#ifndef RTL_MIN_CONE_SLOPE -# define RTL_MIN_CONE_SLOPE 0.5f // minimum slope of cone -#endif - -#ifndef RTL_LOITER_TIME -# define RTL_LOITER_TIME 5000 // Time (in milliseconds) to loiter above home before begining final descent -#endif - // AUTO Mode #ifndef WP_YAW_BEHAVIOR_DEFAULT # define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL @@ -386,11 +287,6 @@ # define YAW_LOOK_AHEAD_MIN_SPEED 100 // minimum ground speed in cm/s required before vehicle is aimed at ground course #endif -// Super Simple mode -#ifndef SUPER_SIMPLE_RADIUS -# define SUPER_SIMPLE_RADIUS 1000 -#endif - ////////////////////////////////////////////////////////////////////////////// // Stabilize Rate Control // @@ -400,9 +296,6 @@ #ifndef DEFAULT_ANGLE_MAX # define DEFAULT_ANGLE_MAX 4500 // ANGLE_MAX parameters default value #endif -#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 ////////////////////////////////////////////////////////////////////////////// // Loiter position control gains @@ -411,16 +304,6 @@ # define POS_XY_P 1.0f #endif -////////////////////////////////////////////////////////////////////////////// -// Stop mode defaults -// -#ifndef BRAKE_MODE_SPEED_Z -# define BRAKE_MODE_SPEED_Z 250 // z-axis speed in cm/s in Brake Mode -#endif -#ifndef BRAKE_MODE_DECEL_RATE -# define BRAKE_MODE_DECEL_RATE 750 // acceleration rate in cm/s/s in Brake Mode -#endif - ////////////////////////////////////////////////////////////////////////////// // Velocity (horizontal) gains // @@ -486,15 +369,6 @@ # define PILOT_ACCEL_Z_DEFAULT 100 // vertical acceleration in cm/s/s while altitude is under pilot control #endif -// max distance in cm above or below current location that will be used for the alt target when transitioning to alt-hold mode -#ifndef ALT_HOLD_INIT_MAX_OVERSHOOT -# define ALT_HOLD_INIT_MAX_OVERSHOOT 200 -#endif -// the acceleration used to define the distance-velocity curve -#ifndef ALT_HOLD_ACCEL_MAX -# define ALT_HOLD_ACCEL_MAX 250 // if you change this you must also update the duplicate declaration in AC_WPNav.h -#endif - #ifndef AUTO_DISARMING_DELAY # define AUTO_DISARMING_DELAY 0 #endif