Plane: added SKIP_GYRO_CAL parameter

useful for starting the sim at high altitudes, and for starting planes
without having to hold them still
This commit is contained in:
Andrew Tridgell 2013-07-20 11:33:09 +10:00
parent c8a83e17d0
commit 74dabad1f3
3 changed files with 35 additions and 10 deletions

View File

@ -91,6 +91,7 @@ public:
k_param_scheduler,
k_param_relay,
k_param_takeoff_throttle_delay,
k_param_skip_gyro_cal,
// 110: Telemetry control
//
@ -278,6 +279,9 @@ public:
// attitude controller type.
AP_Int8 att_controller;
// skip gyro calibration
AP_Int8 skip_gyro_cal;
// Estimation
//
AP_Float altitude_mix;

View File

@ -82,6 +82,13 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Advanced
GSCALAR(stick_mixing, "STICK_MIXING", STICK_MIXING_FBW),
// @Param: SKIP_GYRO_CAL
// @DisplayName: Skip gyro calibration
// @Description: When enabled this tells the APM to skip the normal gyroscope calibration at startup, and instead use the saved gyro calibration from the last flight. You should only enable this if you are careful to check that your aircraft has good attitude control before flying, as some boards may have significantly different gyro calibration between boots, especially if the temperature changes a lot. If gyro calibration is skipped then APM relies on using the gyro drift detection code to get the right gyro calibration in the few minutes after it boots. This option is mostly useful where the requirement to hold the plane still while it is booting is a significant problem.
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
GSCALAR(skip_gyro_cal, "SKIP_GYRO_CAL", 0),
// @Param: TKOFF_THR_MINSPD
// @DisplayName: Takeoff throttle min speed
// @Description: Minimum GPS ground speed in m/s used by the speed check that un-suppresses throttle in auto-takeoff. This can be be used for catapult launches where you want the motor to engage only after the plane leaves the catapult, but it is preferable to use the TKOFF_THR_MINACC and TKOFF_THR_DELAY parameters for cvatapult launches due to the errors associated with GPS measurements. For hand launches with a pusher prop it is strongly advised that this parameter be set to a value no less than 4 m/s to provide additional protection against premature motor start. Note that the GPS velocity will lag the real velocity by about 0.5 seconds. The ground speed check is delayed by the TKOFF_THR_DELAY parameter.

View File

@ -247,7 +247,9 @@ static void startup_ground(void)
// Makes the servos wiggle
// step 1 = 1 wiggle
// -----------------------
demo_servos(1);
if (!g.skip_gyro_cal) {
demo_servos(1);
}
//INS ground start
//------------------------
@ -268,7 +270,9 @@ static void startup_ground(void)
// Makes the servos wiggle - 3 times signals ready to fly
// -----------------------
demo_servos(3);
if (!g.skip_gyro_cal) {
demo_servos(3);
}
// reset last heartbeat time, so we don't trigger failsafe on slow
// startup
@ -435,20 +439,30 @@ static void startup_INS_ground(bool do_accel_init)
}
#endif
gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Warming up ADC..."));
mavlink_delay(500);
AP_InertialSensor::Start_style style;
if (g.skip_gyro_cal && !do_accel_init) {
style = AP_InertialSensor::WARM_START;
} else {
style = AP_InertialSensor::COLD_START;
}
// Makes the servos wiggle twice - about to begin INS calibration - HOLD LEVEL AND STILL!!
// -----------------------
demo_servos(2);
gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Beginning INS calibration; do not move plane"));
mavlink_delay(1000);
if (style == AP_InertialSensor::COLD_START) {
gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Warming up ADC..."));
mavlink_delay(500);
// Makes the servos wiggle twice - about to begin INS calibration - HOLD LEVEL AND STILL!!
// -----------------------
demo_servos(2);
gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Beginning INS calibration; do not move plane"));
mavlink_delay(1000);
}
ahrs.init();
ahrs.set_fly_forward(true);
ahrs.set_wind_estimation(true);
ins.init(AP_InertialSensor::COLD_START,
ins.init(style,
ins_sample_rate,
flash_leds);
if (do_accel_init) {