2012-03-11 05:00:06 -03:00
|
|
|
#ifndef AP_AHRS_HIL_H
|
|
|
|
#define AP_AHRS_HIL_H
|
2010-12-10 06:17:27 -04:00
|
|
|
|
2012-03-11 05:00:06 -03:00
|
|
|
class AP_AHRS_HIL : public AP_AHRS
|
2010-12-10 06:17:27 -04:00
|
|
|
{
|
|
|
|
public:
|
|
|
|
// Constructors
|
2012-03-11 05:00:06 -03:00
|
|
|
AP_AHRS_HIL(IMU *imu, GPS *&gps) : AP_AHRS(imu, gps)
|
|
|
|
{
|
|
|
|
}
|
2010-12-10 06:17:27 -04:00
|
|
|
|
|
|
|
// Accessors
|
2012-03-11 05:00:06 -03:00
|
|
|
Vector3f get_gyro(void) {return _omega; }
|
2011-07-30 17:34:23 -03:00
|
|
|
|
2012-03-11 05:00:06 -03:00
|
|
|
Matrix3f get_dcm_matrix(void) {
|
|
|
|
Matrix3f m;
|
|
|
|
m.from_euler(roll, pitch, yaw);
|
|
|
|
return m;
|
|
|
|
}
|
2010-12-10 06:17:27 -04:00
|
|
|
|
|
|
|
// Methods
|
2012-03-11 05:00:06 -03:00
|
|
|
void update(void) {}
|
|
|
|
void setHil(float roll, float pitch, float yaw,
|
|
|
|
float rollRate, float pitchRate, float yawRate);
|
2011-07-30 17:34:23 -03:00
|
|
|
|
2012-03-11 05:00:06 -03:00
|
|
|
// return the current estimate of the gyro drift
|
|
|
|
Vector3f get_gyro_drift(void) { return Vector3f(0,0,0); }
|
2011-07-30 17:34:23 -03:00
|
|
|
|
2012-03-11 05:00:06 -03:00
|
|
|
// reset the current attitude, used on new IMU calibration
|
|
|
|
void reset(bool recover_eulers=false) {}
|
2011-07-30 17:34:23 -03:00
|
|
|
|
2012-03-11 05:00:06 -03:00
|
|
|
float get_error_rp(void) { return 0; }
|
|
|
|
float get_error_yaw(void) { return 0; }
|
2011-07-30 17:34:23 -03:00
|
|
|
|
2010-12-10 06:17:27 -04:00
|
|
|
private:
|
2012-03-11 05:00:06 -03:00
|
|
|
Vector3f _omega;
|
2010-12-10 06:17:27 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif
|