mirror of https://github.com/ArduPilot/ardupilot
Rover: added SKIP_GYRO_CAL option
This commit is contained in:
parent
6b9b5c5617
commit
c20d0e8152
|
@ -50,6 +50,7 @@ public:
|
|||
k_param_serial0_baud,
|
||||
k_param_serial3_baud,
|
||||
k_param_telem_delay,
|
||||
k_param_skip_gyro_cal,
|
||||
|
||||
//
|
||||
// 130: Sensor parameters
|
||||
|
@ -186,6 +187,7 @@ public:
|
|||
AP_Int8 serial0_baud;
|
||||
AP_Int8 serial3_baud;
|
||||
AP_Int8 telem_delay;
|
||||
AP_Int8 skip_gyro_cal;
|
||||
|
||||
// sensor parameters
|
||||
AP_Int8 compass_enabled;
|
||||
|
|
|
@ -76,6 +76,13 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||
// @Increment: 1
|
||||
GSCALAR(telem_delay, "TELEM_DELAY", 0),
|
||||
|
||||
// @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 vehicle 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: MAG_ENABLED
|
||||
// @DisplayName: Magnetometer (compass) enabled
|
||||
// @Description: This should be set to 1 if a compass is installed
|
||||
|
|
|
@ -347,8 +347,15 @@ static void startup_INS_ground(bool force_accel_level)
|
|||
|
||||
ahrs.init();
|
||||
ahrs.set_fly_forward(true);
|
||||
ins.init(AP_InertialSensor::COLD_START,
|
||||
ins_sample_rate);
|
||||
|
||||
AP_InertialSensor::Start_style style;
|
||||
if (g.skip_gyro_cal && !force_accel_level) {
|
||||
style = AP_InertialSensor::WARM_START;
|
||||
} else {
|
||||
style = AP_InertialSensor::COLD_START;
|
||||
}
|
||||
|
||||
ins.init(style, ins_sample_rate);
|
||||
|
||||
if (force_accel_level) {
|
||||
// when MANUAL_LEVEL is set to 1 we don't do accelerometer
|
||||
|
|
Loading…
Reference in New Issue