mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Copter: move common calibration functions up
This commit is contained in:
parent
5536a321ed
commit
cca4d5136e
@ -943,7 +943,6 @@ private:
|
|||||||
// system.cpp
|
// system.cpp
|
||||||
void init_ardupilot();
|
void init_ardupilot();
|
||||||
void startup_INS_ground();
|
void startup_INS_ground();
|
||||||
bool calibrate_gyros();
|
|
||||||
bool position_ok();
|
bool position_ok();
|
||||||
bool ekf_position_ok();
|
bool ekf_position_ok();
|
||||||
bool optflow_position_ok();
|
bool optflow_position_ok();
|
||||||
|
@ -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)
|
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)) {
|
if (is_equal(packet.param3,1.0f)) {
|
||||||
// fast barometer calibration
|
// fast barometer calibration
|
||||||
copter.init_barometer(false);
|
copter.init_barometer(false);
|
||||||
return MAV_RESULT_ACCEPTED;
|
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)) {
|
if (is_equal(packet.param6,1.0f)) {
|
||||||
// compassmot calibration
|
// compassmot calibration
|
||||||
return copter.mavlink_compassmot(chan);
|
return copter.mavlink_compassmot(chan);
|
||||||
|
@ -301,21 +301,6 @@ void Copter::startup_INS_ground()
|
|||||||
ahrs.reset();
|
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
|
// position_ok - returns true if the horizontal absolute position is ok and home position is set
|
||||||
bool Copter::position_ok()
|
bool Copter::position_ok()
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user