uncrustify libraries/AP_AHRS/AP_AHRS_HIL.h

This commit is contained in:
uncrustify 2012-08-21 19:19:51 -07:00 committed by Pat Hickey
parent b6db467e3c
commit f17b368e38
1 changed files with 32 additions and 22 deletions

View File

@ -4,36 +4,46 @@
class AP_AHRS_HIL : public AP_AHRS class AP_AHRS_HIL : public AP_AHRS
{ {
public: public:
// Constructors // Constructors
AP_AHRS_HIL(IMU *imu, GPS *&gps) : AP_AHRS(imu, gps) AP_AHRS_HIL(IMU *imu, GPS *&gps) : AP_AHRS(imu, gps)
{ {
} }
// Accessors // Accessors
Vector3f get_gyro(void) {return _omega; } Vector3f get_gyro(void) {
return _omega;
}
Matrix3f get_dcm_matrix(void) { Matrix3f get_dcm_matrix(void) {
Matrix3f m; Matrix3f m;
m.from_euler(roll, pitch, yaw); m.from_euler(roll, pitch, yaw);
return m; return m;
} }
// Methods // Methods
void update(void) {} void update(void) {
void setHil(float roll, float pitch, float yaw, }
float rollRate, float pitchRate, float yawRate); void setHil(float roll, float pitch, float yaw,
float rollRate, float pitchRate, float yawRate);
// return the current estimate of the gyro drift // return the current estimate of the gyro drift
Vector3f get_gyro_drift(void) { return Vector3f(0,0,0); } Vector3f get_gyro_drift(void) {
return Vector3f(0,0,0);
}
// reset the current attitude, used on new IMU calibration // reset the current attitude, used on new IMU calibration
void reset(bool recover_eulers=false) {} void reset(bool recover_eulers=false) {
}
float get_error_rp(void) { return 0; } float get_error_rp(void) {
float get_error_yaw(void) { return 0; } return 0;
}
float get_error_yaw(void) {
return 0;
}
private: private:
Vector3f _omega; Vector3f _omega;
}; };
#endif #endif