#pragma once
#include "AP_AHRS.h"
class AC_AttitudeControl;
class AC_PosControl;
class AP_AHRS_View
{
public:
AP_AHRS_View(AP_AHRS &ahrs, enum Rotation rotation, float pitch_trim_deg=0);
void update();
virtual ~AP_AHRS_View() {}
const Vector3f &get_gyro(void) const {
return gyro;
}
Vector3f get_gyro_latest(void) const;
const Matrix3f &get_rotation_body_to_ned(void) const {
return rot_body_to_ned;
}
void get_quat_body_to_ned(Quaternion &quat) const {
quat.from_rotation_matrix(rot_body_to_ned);
}
void set_pitch_trim(float trim_deg);
float get_roll_rad() const { return roll; }
float get_pitch_rad() const { return pitch; }
float get_yaw_rad() const { return yaw; }
float cos_roll() const {
return trig.cos_roll;
}
float cos_pitch() const {
return trig.cos_pitch;
}
float cos_yaw() const {
return trig.cos_yaw;
}
float sin_roll() const {
return trig.sin_roll;
}
float sin_pitch() const {
return trig.sin_pitch;
}
float sin_yaw() const {
return trig.sin_yaw;
}
bool get_location(Location &loc) const WARN_IF_UNUSED {
return ahrs.get_location(loc);
}
bool wind_estimate(Vector3f &wind) {
return ahrs.wind_estimate(wind);
}
bool airspeed_EAS(float &airspeed_ret) const WARN_IF_UNUSED {
return ahrs.airspeed_EAS(airspeed_ret);
}
bool airspeed_TAS(float &airspeed_ret) const WARN_IF_UNUSED {
return ahrs.airspeed_TAS(airspeed_ret);
}
float get_EAS2TAS(void) const {
return ahrs.get_EAS2TAS();
}
Vector2f groundspeed_vector(void) {
return ahrs.groundspeed_vector();
}
bool get_velocity_NED(Vector3f &vec) const WARN_IF_UNUSED {
return ahrs.get_velocity_NED(vec);
}
bool get_relative_position_NED_home(Vector3f &vec) const WARN_IF_UNUSED {
return ahrs.get_relative_position_NED_home(vec);
}
bool get_relative_position_NED_origin_float(Vector3f &vec) const WARN_IF_UNUSED {
return ahrs.get_relative_position_NED_origin_float(vec);
}
bool get_relative_position_NE_home(Vector2f &vecNE) const WARN_IF_UNUSED {
return ahrs.get_relative_position_NE_home(vecNE);
}
bool get_relative_position_NE_origin_float(Vector2f &vecNE) const WARN_IF_UNUSED {
return ahrs.get_relative_position_NE_origin_float(vecNE);
}
void get_relative_position_D_home(float &posD) const {
ahrs.get_relative_position_D_home(posD);
}
bool get_relative_position_D_origin_float(float &posD) const WARN_IF_UNUSED {
return ahrs.get_relative_position_D_origin_float(posD);
}
float groundspeed(void) {
return ahrs.groundspeed();
}
const Vector3f &get_accel_ef(void) const {
return ahrs.get_accel_ef();
}
uint32_t getLastPosNorthEastReset(Vector2f &pos) WARN_IF_UNUSED {
return ahrs.getLastPosNorthEastReset(pos);
}
uint32_t getLastPosDownReset(float &posDelta) WARN_IF_UNUSED {
return ahrs.getLastPosDownReset(posDelta);
}
Vector2f earth_to_body2D(const Vector2f &ef_vector) const;
Vector2f body_to_earth2D(const Vector2f &bf) const;
float get_error_rp(void) const {
return ahrs.get_error_rp();
}
float get_error_yaw(void) const {
return ahrs.get_error_yaw();
}
void Write_AttitudeView(const Vector3f &targets) const;
float roll;
float pitch;
float yaw;
int32_t roll_sensor;
int32_t pitch_sensor;
int32_t yaw_sensor;
enum Rotation get_rotation(void) const {
return rotation;
}
float get_pitch_trim() const { return _pitch_trim_deg; }
void rotate(Vector3f &vec) const;
private:
const enum Rotation rotation;
AP_AHRS &ahrs;
Matrix3f rot_view;
Matrix3f rot_view_T;
Matrix3f rot_body_to_ned;
Vector3f gyro;
struct {
float cos_roll;
float cos_pitch;
float cos_yaw;
float sin_roll;
float sin_pitch;
float sin_yaw;
} trig;
float y_angle;
float _pitch_trim_deg;
};