From cca4d5136e46dccc35851d30bf580eb3e1cf72be Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 17 Mar 2018 23:12:33 +1100 Subject: [PATCH] Copter: move common calibration functions up --- ArduCopter/Copter.h | 1 - ArduCopter/GCS_Mavlink.cpp | 40 -------------------------------------- ArduCopter/system.cpp | 15 -------------- 3 files changed, 56 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 1d71504ece..2bee51206b 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -943,7 +943,6 @@ private: // system.cpp void init_ardupilot(); void startup_INS_ground(); - bool calibrate_gyros(); bool position_ok(); bool ekf_position_ok(); bool optflow_position_ok(); diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index b723bcf78c..6c734210b1 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -720,52 +720,12 @@ void GCS_MAVLINK_Copter::handle_command_ack(const mavlink_message_t* msg) MAV_RESULT GCS_MAVLINK_Copter::_handle_command_preflight_calibration(const mavlink_command_long_t &packet) { - if (is_equal(packet.param1,1.0f)) { - if (!copter.calibrate_gyros()) { - return MAV_RESULT_FAILED; - } - return MAV_RESULT_ACCEPTED; - } - if (is_equal(packet.param3,1.0f)) { // fast barometer calibration copter.init_barometer(false); return MAV_RESULT_ACCEPTED; } - if (is_equal(packet.param4,1.0f)) { - return MAV_RESULT_UNSUPPORTED; - } - - if (is_equal(packet.param5,1.0f)) { - // 3d accel calibration - if (!copter.calibrate_gyros()) { - return MAV_RESULT_FAILED; - } - copter.ins.acal_init(); - copter.ins.get_acal()->start(this); - return MAV_RESULT_ACCEPTED; - } - - if (is_equal(packet.param5,2.0f)) { - // calibrate gyros - if (!copter.calibrate_gyros()) { - return MAV_RESULT_FAILED; - } - // accel trim - float trim_roll, trim_pitch; - if(!copter.ins.calibrate_trim(trim_roll, trim_pitch)) { - return MAV_RESULT_FAILED; - } - // reset ahrs's trim to suggested values from calibration routine - copter.ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0)); - return MAV_RESULT_ACCEPTED; - } - - if (is_equal(packet.param5,4.0f)) { - // simple accel calibration - return copter.ins.simple_accel_cal(copter.ahrs); - } if (is_equal(packet.param6,1.0f)) { // compassmot calibration return copter.mavlink_compassmot(chan); diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index bc4a9cf905..b7feb2353f 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -301,21 +301,6 @@ void Copter::startup_INS_ground() ahrs.reset(); } -// calibrate gyros - returns true if successfully calibrated -bool Copter::calibrate_gyros() -{ - // gyro offset calibration - copter.ins.init_gyro(); - - // reset ahrs gyro bias - if (copter.ins.gyro_calibrated_ok_all()) { - copter.ahrs.reset_gyro_drift(); - return true; - } - - return false; -} - // position_ok - returns true if the horizontal absolute position is ok and home position is set bool Copter::position_ok() {