diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 978f4bef50..05b42f125a 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -468,7 +468,7 @@ const AP_Param::Info Sub::var_info[] = { // @Values: 0:Disabled, 1:Enabled, -3:Skip Baro, -5:Skip Compass, -9:Skip GPS, -17:Skip INS, -33:Skip Params/Rangefinder, -65:Skip RC, 127:Skip Voltage // @Bitmask: 0:All,1:Baro,2:Compass,3:GPS,4:INS,5:Parameters+Rangefinder,6:RC,7:Voltage // @User: Standard - GSCALAR(arming_check, "ARMING_CHECK", ARMING_CHECK_ALL), + GSCALAR(arming_check, "ARMING_CHECK", -66), // @Param: DISARM_DELAY // @DisplayName: Disarm delay diff --git a/ArduSub/config.h b/ArduSub/config.h index ccb73c7cbd..0ce335f14b 100644 --- a/ArduSub/config.h +++ b/ArduSub/config.h @@ -514,7 +514,7 @@ #endif #ifndef THR_MIN_DEFAULT - # define THR_MIN_DEFAULT 130 // minimum throttle sent to the motors when armed and pilot throttle above zero + # define THR_MIN_DEFAULT 0 // minimum throttle sent to the motors when armed and pilot throttle above zero #endif #define THR_MAX 1000 // maximum throttle input and output sent to the motors @@ -550,10 +550,10 @@ // default maximum vertical velocity and acceleration the pilot may request #ifndef PILOT_VELZ_MAX - # define PILOT_VELZ_MAX 250 // maximum vertical velocity in cm/s + # define PILOT_VELZ_MAX 50 // maximum vertical velocity in cm/s #endif #ifndef PILOT_ACCEL_Z_DEFAULT - # define PILOT_ACCEL_Z_DEFAULT 250 // vertical acceleration in cm/s/s while altitude is under pilot control + # define PILOT_ACCEL_Z_DEFAULT 50 // 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