mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AntennaTracker: removed 1D accel cal
This commit is contained in:
parent
5175f21225
commit
bd4476cb84
@ -519,10 +519,16 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
|
|
||||||
case MAV_CMD_PREFLIGHT_CALIBRATION:
|
case MAV_CMD_PREFLIGHT_CALIBRATION:
|
||||||
{
|
{
|
||||||
if (packet.param1 == 1 ||
|
if (packet.param1 == 1) {
|
||||||
packet.param2 == 1) {
|
ins.init_gyro();
|
||||||
calibrate_ins();
|
if (ins.gyro_calibrated_ok_all()) {
|
||||||
} else if (packet.param3 == 1) {
|
ahrs.reset_gyro_drift();
|
||||||
|
result = MAV_RESULT_ACCEPTED;
|
||||||
|
} else {
|
||||||
|
result = MAV_RESULT_FAILED;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (packet.param3 == 1) {
|
||||||
init_barometer();
|
init_barometer();
|
||||||
// zero the altitude difference on next baro update
|
// zero the altitude difference on next baro update
|
||||||
nav_status.need_altitude_calibration = true;
|
nav_status.need_altitude_calibration = true;
|
||||||
@ -531,7 +537,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
// Cant trim radio
|
// Cant trim radio
|
||||||
}
|
}
|
||||||
#if !defined( __AVR_ATmega1280__ )
|
#if !defined( __AVR_ATmega1280__ )
|
||||||
if (packet.param5 == 1) {
|
else if (packet.param5 == 1) {
|
||||||
float trim_roll, trim_pitch;
|
float trim_roll, trim_pitch;
|
||||||
AP_InertialSensor_UserInteract_MAVLink interact(this);
|
AP_InertialSensor_UserInteract_MAVLink interact(this);
|
||||||
if(ins.calibrate_accel(&interact, trim_roll, trim_pitch)) {
|
if(ins.calibrate_accel(&interact, trim_roll, trim_pitch)) {
|
||||||
|
@ -99,19 +99,6 @@ static void init_tracker()
|
|||||||
nav_status.need_altitude_calibration = true;
|
nav_status.need_altitude_calibration = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Level the tracker by calibrating the INS
|
|
||||||
// Requires that the tracker be physically 'level' and horizontal
|
|
||||||
static void calibrate_ins()
|
|
||||||
{
|
|
||||||
gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Beginning INS calibration; do not move tracker"));
|
|
||||||
ahrs.init();
|
|
||||||
ins.init(AP_InertialSensor::COLD_START, ins_sample_rate);
|
|
||||||
ins.init_accel();
|
|
||||||
ahrs.set_trim(Vector3f(0, 0, 0));
|
|
||||||
ahrs.reset();
|
|
||||||
init_barometer();
|
|
||||||
}
|
|
||||||
|
|
||||||
// updates the status of the notify objects
|
// updates the status of the notify objects
|
||||||
// should be called at 50hz
|
// should be called at 50hz
|
||||||
static void update_notify()
|
static void update_notify()
|
||||||
|
Loading…
Reference in New Issue
Block a user