mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: rename ins get_primary_accel to get_first_usable_accel
This commit is contained in:
parent
8ddac54b17
commit
8302e0d1e2
|
@ -245,7 +245,7 @@ void SoloGimbal::update_fast() {
|
|||
// single gyro mode - one of the first two gyros are unhealthy or don't exist
|
||||
// just read primary gyro
|
||||
Vector3f dAng;
|
||||
readVehicleDeltaAngle(ins.get_primary_gyro(), dAng);
|
||||
readVehicleDeltaAngle(ins.get_first_usable_gyro(), dAng);
|
||||
_vehicle_delta_angles += dAng;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue