mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_Mount: use ins singleton
This commit is contained in:
parent
f0d06e7a9c
commit
9f556197a0
@ -209,7 +209,7 @@ void SoloGimbal::update_estimators()
|
||||
}
|
||||
|
||||
void SoloGimbal::readVehicleDeltaAngle(uint8_t ins_index, Vector3f &dAng) {
|
||||
const AP_InertialSensor &ins = _ahrs.get_ins();
|
||||
const AP_InertialSensor &ins = AP::ins();
|
||||
|
||||
if (ins_index < ins.get_gyro_count()) {
|
||||
if (!ins.get_delta_angle(ins_index,dAng)) {
|
||||
@ -219,7 +219,7 @@ void SoloGimbal::readVehicleDeltaAngle(uint8_t ins_index, Vector3f &dAng) {
|
||||
}
|
||||
|
||||
void SoloGimbal::update_fast() {
|
||||
const AP_InertialSensor &ins = _ahrs.get_ins();
|
||||
const AP_InertialSensor &ins = AP::ins();
|
||||
|
||||
if (ins.get_gyro_health(0) && ins.get_gyro_health(1)) {
|
||||
// dual gyro mode - average first two gyros
|
||||
|
Loading…
Reference in New Issue
Block a user