AP_AHRS Detailed Reference¶
Header¶
File: libraries/AP_AHRS/AP_AHRS.h
#include <AP_AHRS.h>
Class Documentation¶
-
class AP_AHRS¶
Detailed Description¶
AP_AHRS (Attitude and Heading Reference System) is the central navigation system for ArduPilot. It uses sensor fusion (Extended Kalman Filter - EKF) to combine data from GPS, compass, gyroscopes, and accelerometers to provide accurate attitude estimation.
Key Features:
Extended Kalman Filter (EKF) for attitude estimation
GPS fusion for position
Compass fusion for heading
Sensor redundancy handling
Multiple EKF lanes for safety
Airspeed estimation
Wind estimation
Inheritance¶
This class does not inherit from any other class. It is a top-level class.
Related Classes:
:doxygen:`AP_AHRS_View` - View into another AHRS instance
:doxygen:`AP_AHRS_Backend` - Base class for AHRS backends
EKF2/EKF3 - Extended Kalman Filter implementations
Public Types¶
Public Member Functions¶
Singleton¶
Initialization & Update¶
Attitude (Euler Angles)¶
-
float AP_AHRS::get_roll_deg() const¶
Get current roll angle in degrees.
- Returns:
Roll angle in degrees
-
float AP_AHRS::get_pitch_deg() const¶
Get current pitch angle in degrees.
- Returns:
Pitch angle in degrees
-
Vector3f get_roll_pitch_yaw() const¶
Get all euler angles as a vector.
- Returns:
Vector3f containing roll, pitch, yaw in radians
Quaternion¶
Rotation Matrices¶
Gyro & Accelerometer¶
-
const Vector3f &AP_AHRS::get_gyro(void) const¶
Get estimated gyro values.
- Returns:
Gyro vector in rad/s
-
const Vector3f &AP_AHRS::get_accel(void) const¶
Get estimated accelerometer values.
- Returns:
Acceleration vector in m/s^2
-
const Vector3f &get_accel_ef() const¶
Get acceleration in earth frame.
- Returns:
Earth-frame acceleration
Position¶
-
bool AP_AHRS::get_location(Location &loc) const¶
Get current GPS location.
- Parameters:
loc – Output Location struct
- Returns:
true if location is available
Velocity¶
Airspeed¶
-
bool AP_AHRS::airspeed_EAS(float &airspeed_ret) const¶
Get Equivalent Airspeed (EAS).
- Parameters:
airspeed_ret – Output airspeed in m/s
- Returns:
true if airspeed is available
Wind Estimation¶
-
const Vector3f &AP_AHRS::wind_estimate() const¶
Get estimated wind velocity.
- Returns:
Wind vector in NED frame (m/s)
Health & Status¶
Get EKF filter status.
- Parameters:
status – Output status structure
- Returns:
true if status available
Home Position¶
Trim Values¶
-
const Vector3f &AP_AHRS::get_trim() const¶
Get trim values.
- Returns:
Trim vector (roll, pitch, yaw) in radians
EKF Control¶
Usage Example¶
#include <AP_AHRS.h>
AP_AHRS &ahrs = AP_AHRS::get_singleton();
void setup() {
// Initialize AHRS
ahrs.init();
}
void loop() {
// Update AHRS (typically 100Hz)
ahrs.update();
// Get attitude
float roll = ahrs.get_roll(); // radians
float pitch = ahrs.get_pitch(); // radians
float yaw = ahrs.get_yaw(); // radians
// Get as degrees
float roll_deg = ahrs.get_roll_deg();
float pitch_deg = ahrs.get_pitch_deg();
float yaw_deg = ahrs.get_yaw_deg();
Serial.printf("Attitude: R=%.1f, P=%.1f, Y=%.1f\n",
roll_deg, pitch_deg, yaw_deg);
// Get ground speed
float ground_speed = ahrs.groundspeed();
Serial.printf("Ground Speed: %.2f m/s\n", ground_speed);
// Get position
Location loc;
if (ahrs.get_location(loc)) {
Serial.printf("Position: %.6f, %.6f, %.0f\n",
loc.lat / 1e7, loc.lng / 1e7, loc.alt / 100.0);
}
// Get velocity
Vector3f vel;
if (ahrs.get_velocity_NED(vel)) {
Serial.printf("Velocity: N=%.2f, E=%.2f, D=%.2f m/s\n",
vel.x, vel.y, vel.z);
}
// Get wind estimate
Vector3f wind = ahrs.wind_estimate();
Serial.printf("Wind: N=%.2f, E=%.2f, D=%.2f m/s\n",
wind.x, wind.y, wind.z);
}
See Also¶
Sensor Libraries - Overview of sensor libraries
api/ap_gps - GPS sensor for position
api/ap_compass - Compass for heading
api/ap_baro - Barometer for altitude
Control Libraries - Control libraries (uses AHRS)