mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 18:23:57 -04:00
Plane: removed the MANUAL_LEVEL option
levelling on every startup is far too error prone. This was just another parameter that everyone changed.
This commit is contained in:
parent
3d7a4d0e6e
commit
de3fcbc413
@ -1136,7 +1136,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
case MAV_CMD_PREFLIGHT_CALIBRATION:
|
||||
if (packet.param1 == 1 ||
|
||||
packet.param2 == 1) {
|
||||
startup_INS_ground(true);
|
||||
startup_INS_ground();
|
||||
} else if (packet.param3 == 1) {
|
||||
init_barometer();
|
||||
if (airspeed.enabled()) {
|
||||
|
@ -66,7 +66,7 @@ public:
|
||||
k_param_flap_2_percent,
|
||||
k_param_flap_2_speed,
|
||||
k_param_reset_switch_chan,
|
||||
k_param_manual_level,
|
||||
k_param_manual_level, // unused
|
||||
k_param_land_pitch_cd,
|
||||
k_param_ins_old, // *** Deprecated, remove with next eeprom number change
|
||||
k_param_stick_mixing,
|
||||
@ -338,7 +338,6 @@ public:
|
||||
AP_Int16 log_bitmask;
|
||||
AP_Int8 reset_switch_chan;
|
||||
AP_Int8 reset_mission_chan;
|
||||
AP_Int8 manual_level;
|
||||
AP_Int32 airspeed_cruise_cm;
|
||||
AP_Int32 RTL_altitude_cm;
|
||||
AP_Int16 land_pitch_cd;
|
||||
|
@ -74,13 +74,6 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @User: Advanced
|
||||
GSCALAR(kff_throttle_to_pitch, "KFF_THR2PTCH", T_TO_P),
|
||||
|
||||
// @Param: MANUAL_LEVEL
|
||||
// @DisplayName: Manual Level
|
||||
// @Description: Setting this to Disabled(0) will enable autolevel on every boot. Setting it to Enabled(1) will do a calibration only when you tell it to
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Advanced
|
||||
GSCALAR(manual_level, "MANUAL_LEVEL", MANUAL_LEVEL),
|
||||
|
||||
// @Param: STICK_MIXING
|
||||
// @DisplayName: Stick Mixing
|
||||
// @Description: When enabled, this adds user stick input to the control surfaces in auto modes, allowing the user to have some degree of flight control without changing modes. There are two types of stick mixing available. If you set STICK_MIXING to 1 then it will use "fly by wire" mixing, which controls the roll and pitch in the same way that the FBWA mode does. This is the safest option if you usually fly ArduPlane in FBWA or FBWB mode. If you set STICK_MIXING to 2 then it will enable direct mixing mode, which is what the STABILIZE mode uses. That will allow for much more extreme maneuvers while in AUTO mode.
|
||||
@ -528,7 +521,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
|
||||
// @Param: TRIM_PITCH_CD
|
||||
// @DisplayName: Pitch angle offset
|
||||
// @Description: offset to add to pitch - used for trimming tail draggers
|
||||
// @Description: offset to add to pitch - used for in-flight pitch trimming. It is recommended that instead of using this parameter you level your plane correctly on the ground for good flight attitude.
|
||||
// @Units: centi-Degrees
|
||||
// @User: Advanced
|
||||
GSCALAR(pitch_trim_cd, "TRIM_PITCH_CD", 0),
|
||||
|
@ -407,13 +407,6 @@
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Level with each startup = 0, level with MP/CLI only = 1
|
||||
//
|
||||
#ifndef MANUAL_LEVEL
|
||||
# define MANUAL_LEVEL 0
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// GROUND_START_DELAY
|
||||
//
|
||||
|
@ -376,7 +376,7 @@ setup_erase(uint8_t argc, const Menu::arg *argv)
|
||||
static int8_t
|
||||
setup_level(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
startup_INS_ground(true);
|
||||
startup_INS_ground();
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -402,10 +402,6 @@ setup_accel_scale(uint8_t argc, const Menu::arg *argv)
|
||||
if (success) {
|
||||
// reset ahrs's trim to suggested values from calibration routine
|
||||
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
|
||||
if (g.manual_level == 0) {
|
||||
cliSerial->println_P(PSTR("Setting MANUAL_LEVEL to 1"));
|
||||
g.manual_level.set_and_save(1);
|
||||
}
|
||||
}
|
||||
report_ins();
|
||||
return(0);
|
||||
|
@ -282,7 +282,7 @@ static void startup_ground(void)
|
||||
//INS ground start
|
||||
//------------------------
|
||||
//
|
||||
startup_INS_ground(false);
|
||||
startup_INS_ground();
|
||||
|
||||
// read the radio to set trims
|
||||
// ---------------------------
|
||||
@ -428,7 +428,7 @@ static void check_short_failsafe()
|
||||
}
|
||||
|
||||
|
||||
static void startup_INS_ground(bool force_accel_level)
|
||||
static void startup_INS_ground(void)
|
||||
{
|
||||
#if HIL_MODE != HIL_MODE_DISABLED
|
||||
while (!barometer.healthy) {
|
||||
@ -454,15 +454,6 @@ static void startup_INS_ground(bool force_accel_level)
|
||||
ins.init(AP_InertialSensor::COLD_START,
|
||||
ins_sample_rate,
|
||||
flash_leds);
|
||||
#if HIL_MODE == HIL_MODE_DISABLED
|
||||
if (force_accel_level || g.manual_level == 0) {
|
||||
// when MANUAL_LEVEL is set to 1 we don't do accelerometer
|
||||
// levelling on each boot, and instead rely on the user to do
|
||||
// it once via the ground station
|
||||
ins.init_accel(flash_leds);
|
||||
ahrs.set_trim(Vector3f(0, 0, 0));
|
||||
}
|
||||
#endif
|
||||
ahrs.reset();
|
||||
|
||||
// read Baro pressure at ground
|
||||
|
Loading…
Reference in New Issue
Block a user