mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AntennaTracker: support setting just accel trim with preflight-cal
use param5==2
This commit is contained in:
parent
fb435fc78e
commit
4a290cd2f1
@ -601,17 +601,24 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
}
|
}
|
||||||
if (is_equal(packet.param4,1.0f)) {
|
if (is_equal(packet.param4,1.0f)) {
|
||||||
// Cant trim radio
|
// Cant trim radio
|
||||||
}
|
} else if (is_equal(packet.param5,1.0f)) {
|
||||||
#if !defined( __AVR_ATmega1280__ )
|
|
||||||
else if (is_equal(packet.param5,1.0f)) {
|
|
||||||
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)) {
|
||||||
// reset ahrs's trim to suggested values from calibration routine
|
// reset ahrs's trim to suggested values from calibration routine
|
||||||
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
|
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
|
||||||
}
|
}
|
||||||
|
} else if (is_equal(packet.param5,2.0f)) {
|
||||||
|
// accel trim
|
||||||
|
float trim_roll, trim_pitch;
|
||||||
|
if(ins.calibrate_trim(trim_roll, trim_pitch)) {
|
||||||
|
// reset ahrs's trim to suggested values from calibration routine
|
||||||
|
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
|
||||||
|
result = MAV_RESULT_ACCEPTED;
|
||||||
|
} else {
|
||||||
|
result = MAV_RESULT_FAILED;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user