34 #define AP_AHRS_TRIM_LIMIT 10.0f // maximum trim angle in degrees 35 #define AP_AHRS_RP_P_MIN 0.05f // minimum value for AHRS_RP_P parameter 36 #define AP_AHRS_YAW_P_MIN 0.05f // minimum value for AHRS_YAW_P parameter 211 virtual void update(
bool skip_ins_update=
false) = 0;
247 virtual void reset(
bool recover_eulers=
false) = 0;
250 virtual void reset_attitude(
const float &roll,
const float &pitch,
const float &yaw) = 0;
270 virtual bool get_hagl(
float &height)
const {
return false; }
393 virtual void add_trim(
float roll_in_radians,
float pitch_in_radians,
bool save_to_eeprom =
true);
480 virtual bool healthy(
void)
const = 0;
529 virtual uint32_t
uptime_ms(
void)
const = 0;
607 float &cr,
float &cp,
float &cy,
608 float &sr,
float &sp,
float &sy)
const;
681 #if AP_AHRS_NAVEKF_AVAILABLE 682 #define AP_AHRS_TYPE AP_AHRS_NavEKF 684 #define AP_AHRS_TYPE AP_AHRS
static const struct AP_Param::GroupInfo var_info[]
virtual uint32_t getLastPosNorthEastReset(Vector2f &pos) const
virtual bool get_hagl(float &height) const
bool yaw_initialised(void) const
virtual bool get_velocity_NED(Vector3f &vec) const
const Vector3f & get_trim() const
void set_compass(Compass *compass)
bool airspeed_estimate_true(float *airspeed_ret) const
virtual uint32_t getLastPosDownReset(float &posDelta) const
bool use_for_yaw(uint8_t i) const
return true if the compass should be used for yaw calculations
virtual void update(bool skip_ins_update=false)=0
const OpticalFlow * _optflow
virtual void getCorrectedDeltaVelocityNED(Vector3f &ret, float &dt) const
void set_airspeed(AP_Airspeed *airspeed)
virtual bool have_ekf_logging(void) const
virtual const Vector3f & get_accel_ef_blended(void) const
virtual const Vector3f & get_gyro(void) const =0
virtual void reset_attitude(const float &roll, const float &pitch, const float &yaw)=0
virtual bool get_position(struct Location &loc) const =0
virtual bool get_relative_position_NED_home(Vector3f &vec) const
virtual Vector3f wind_estimate(void) const =0
AP_Int8 _board_orientation
const struct Location & get_home(void) const
virtual void set_home(const Location &loc)=0
virtual uint32_t getLastVelNorthEastReset(Vector2f &vel) const
uint8_t get_primary_gyro(void) const
virtual bool get_relative_position_NED_origin(Vector3f &vec) const
AHRS_VehicleClass get_vehicle_class(void) const
virtual float get_error_yaw(void) const =0
virtual const char * prearm_failure_reason(void) const
virtual bool get_relative_position_NE_origin(Vector2f &vecNE) const
AHRS_VehicleClass _vehicle_class
void from_euler(float roll, float pitch, float yaw)
virtual void reset_gyro_drift(void)=0
virtual void reset(bool recover_eulers=false)=0
virtual bool airspeed_estimate(float *airspeed_ret) const
float get_yaw_rate_earth(void) const
virtual bool get_secondary_quaternion(Quaternion &quat) const
bool get_delta_velocity(uint8_t i, Vector3f &delta_velocity) const
virtual bool initialised(void) const
void Log_Write_Home_And_Origin()
Vector3f _accel_ef_blended
bool get_likely_flying(void) const
virtual Vector2f groundspeed_vector(void)
virtual void update_AOA_SSA(void)
virtual const Matrix3f & get_rotation_body_to_ned(void) const =0
uint8_t correct_centrifugal
static AP_AHRS * get_singleton()
AP_AHRS_View * create_view(enum Rotation rotation)
void set_likely_flying(bool b)
Vector2f rotate_earth_to_body2D(const Vector2f &ef_vector) const
virtual void add_trim(float roll_in_radians, float pitch_in_radians, bool save_to_eeprom=true)
Matrix3f _rotation_vehicle_body_to_autopilot_body
virtual bool have_inertial_nav(void) const
virtual const Vector3f & get_accel_ef(void) const
void set_wind_estimation(bool b)
const Compass * get_compass() const
const AP_Airspeed * get_airspeed(void) const
A system for managing and storing variables that are of general interest to the system.
Matrix3< T > transposed(void) const
uint8_t get_primary_accel(void) const
Matrix3f _custom_rotation
virtual uint32_t uptime_ms(void) const =0
virtual void set_trim(Vector3f new_trim)
void set_fly_forward(bool b)
virtual void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
void update_cd_values(void)
int8_t get_ekf_type(void) const
virtual const Vector3f & get_accel_ef(uint8_t i) const
static OpticalFlow optflow
void set_correct_centrifugal(bool setting)
Matrix3f _rotation_autopilot_body_to_vehicle_body
void set_vehicle_class(AHRS_VehicleClass vclass)
virtual bool get_relative_position_NE_home(Vector2f &vecNE) const
Vector2f rotate_body_to_earth2D(const Vector2f &bf) const
Vector3f get_gyro_latest(void) const
const Matrix3f & get_rotation_vehicle_body_to_autopilot_body(void) const
virtual const Vector3f & get_gyro_drift(void) const =0
bool get_correct_centrifugal(void) const
void set_optflow(const OpticalFlow *optflow)
virtual float get_error_rp(void) const =0
uint8_t get_active_accel_instance(void) const
uint8_t _active_accel_instance
const Matrix3f & get_rotation_autopilot_body_to_vehicle_body(void) const
Vector3f _accel_ef[INS_MAX_INSTANCES]
float get_EAS2TAS(uint8_t i) const
bool home_is_locked() const
float get_delta_velocity_dt(uint8_t i) const
const OpticalFlow * get_optflow() const
virtual bool get_hgt_ctrl_limit(float &limit) const
virtual uint8_t get_primary_accel_index(void) const
virtual bool healthy(void) const =0
virtual bool use_compass(void)
bool get_fly_forward(void) const
virtual uint32_t getLastYawResetAngle(float &yawAng) const
void set_beacon(AP_Beacon *beacon)
virtual bool get_origin(Location &ret) const
uint32_t _compass_last_update
virtual bool get_secondary_attitude(Vector3f &eulers) const
virtual bool get_secondary_position(struct Location &loc) const
const AP_Beacon * get_beacon(void) const
uint32_t get_time_flying_ms(void) const
virtual uint8_t get_primary_gyro_index(void) const
virtual bool get_expected_mag_field_NED(Vector3f &ret) const
AP_InertialSensor & ins()
struct AP_AHRS::ahrs_flags _flags
void calc_trig(const Matrix3f &rot, float &cr, float &cp, float &cy, float &sr, float &sp, float &sy) const
bool airspeed_sensor_enabled(void) const
float get_EAS2TAS(void) const
virtual bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
#define INS_MAX_INSTANCES
bool home_is_set(void) const
virtual bool get_mag_field_correction(Vector3f &ret) const
bool healthy(uint8_t i) const
virtual void get_relative_position_D_home(float &posD) const =0
static AP_AHRS * _singleton
virtual bool get_relative_position_D_origin(float &posD) const
virtual bool set_origin(const Location &loc)
float get_gyro_drift_rate(void) const
uint32_t _last_AOA_update_ms
virtual bool resetHeightDatum(void)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)