mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Arming: remove unused set_skip_gyro_cal
This commit is contained in:
parent
87cada1d54
commit
73e7e64bb8
@ -44,7 +44,6 @@ AP_Arming::AP_Arming(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &comp
|
||||
const enum HomeState &home_set)
|
||||
: armed(false)
|
||||
, logging_available(false)
|
||||
, skip_gyro_cal(false)
|
||||
, arming_method(NONE)
|
||||
, ahrs(ahrs_ref)
|
||||
, barometer(baro)
|
||||
@ -130,7 +129,7 @@ bool AP_Arming::ins_checks(bool report)
|
||||
}
|
||||
return false;
|
||||
}
|
||||
if (!skip_gyro_cal && ! ins.gyro_calibrated_ok_all()) {
|
||||
if (!ins.gyro_calibrated_ok_all()) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: gyros not calibrated!"));
|
||||
}
|
||||
|
@ -58,7 +58,6 @@ public:
|
||||
in a vehicle specific subclass
|
||||
*/
|
||||
virtual bool pre_arm_checks(bool report);
|
||||
void set_skip_gyro_cal(bool set) { skip_gyro_cal = set; }
|
||||
|
||||
void set_logging_available(bool set) { logging_available = set; }
|
||||
|
||||
@ -68,7 +67,6 @@ public:
|
||||
protected:
|
||||
bool armed:1;
|
||||
bool logging_available:1;
|
||||
bool skip_gyro_cal:1;
|
||||
|
||||
//Parameters
|
||||
AP_Int8 require;
|
||||
|
Loading…
Reference in New Issue
Block a user