AP_AHRS: mark many functions as override

Also take the opportunity to remove void parameter
This commit is contained in:
Peter Barker 2017-02-23 21:27:21 +11:00 committed by Andrew Tridgell
parent 6ee4045878
commit e744460ff5
2 changed files with 42 additions and 42 deletions

View File

@ -59,44 +59,44 @@ public:
}
// return the smoothed gyro vector corrected for drift
const Vector3f &get_gyro(void) const {
const Vector3f &get_gyro() const override {
return _omega;
}
// return rotation matrix representing rotaton from body to earth axes
const Matrix3f &get_rotation_body_to_ned(void) const {
const Matrix3f &get_rotation_body_to_ned() const override {
return _body_dcm_matrix;
}
// return the current drift correction integrator value
const Vector3f &get_gyro_drift(void) const {
const Vector3f &get_gyro_drift() const override {
return _omega_I;
}
// reset the current gyro drift estimate
// should be called if gyro offsets are recalculated
void reset_gyro_drift(void);
void reset_gyro_drift() override;
// Methods
void update(void);
void reset(bool recover_eulers = false);
void update() override;
void reset(bool recover_eulers = false) override;
// reset the current attitude, used on new IMU calibration
void reset_attitude(const float &roll, const float &pitch, const float &yaw);
void reset_attitude(const float &roll, const float &pitch, const float &yaw) override;
// dead-reckoning support
virtual bool get_position(struct Location &loc) const;
virtual bool get_position(struct Location &loc) const override;
// status reporting
float get_error_rp(void) const {
float get_error_rp() const override {
return _error_rp;
}
float get_error_yaw(void) const {
float get_error_yaw() const override {
return _error_yaw;
}
// return a wind estimation vector, in m/s
Vector3f wind_estimate(void) {
Vector3f wind_estimate() override {
return _wind;
}
@ -104,18 +104,18 @@ public:
// return an airspeed estimate if available. return true
// if we have an estimate
bool airspeed_estimate(float *airspeed_ret) const;
bool airspeed_estimate(float *airspeed_ret) const override;
bool use_compass(void);
bool use_compass() override;
void set_home(const Location &loc);
void set_home(const Location &loc) override;
void estimate_wind(void);
// is the AHRS subsystem healthy?
bool healthy(void) const;
bool healthy() const override;
// time that the AHRS has been up
uint32_t uptime_ms(void) const;
uint32_t uptime_ms() const override;
private:
float _ki;

View File

@ -57,33 +57,33 @@ public:
// reset the current gyro drift estimate
// should be called if gyro offsets are recalculated
void reset_gyro_drift(void);
void reset_gyro_drift() override;
void update(void);
void reset(bool recover_eulers = false);
void update() override;
void reset(bool recover_eulers = false) override;
// reset the current attitude, used on new IMU calibration
void reset_attitude(const float &roll, const float &pitch, const float &yaw);
void reset_attitude(const float &roll, const float &pitch, const float &yaw) override;
// dead-reckoning support
bool get_position(struct Location &loc) const;
bool get_position(struct Location &loc) const override;
// get latest altitude estimate above ground level in meters and validity flag
bool get_hagl(float &hagl) const;
// status reporting of estimated error
float get_error_rp(void) const;
float get_error_yaw(void) const;
float get_error_rp() const override;
float get_error_yaw() const override;
// return a wind estimation vector, in m/s
Vector3f wind_estimate(void);
Vector3f wind_estimate() override;
// return an airspeed estimate if available. return true
// if we have an estimate
bool airspeed_estimate(float *airspeed_ret) const;
bool airspeed_estimate(float *airspeed_ret) const override;
// true if compass is being used
bool use_compass(void);
bool use_compass() override;
// we will need to remove these to fully hide which EKF we are using
NavEKF2 &get_NavEKF2(void) {
@ -101,32 +101,32 @@ public:
}
// return secondary attitude solution if available, as eulers in radians
bool get_secondary_attitude(Vector3f &eulers);
bool get_secondary_attitude(Vector3f &eulers) override;
// return secondary position solution if available
bool get_secondary_position(struct Location &loc);
bool get_secondary_position(struct Location &loc) override;
// EKF has a better ground speed vector estimate
Vector2f groundspeed_vector(void);
Vector2f groundspeed_vector() override;
const Vector3f &get_accel_ef(uint8_t i) const override;
const Vector3f &get_accel_ef() const override;
// Retrieves the corrected NED delta velocity in use by the inertial navigation
void getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const;
void getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const override;
// blended accelerometer values in the earth frame in m/s/s
const Vector3f &get_accel_ef_blended(void) const;
const Vector3f &get_accel_ef_blended() const override;
// set home location
void set_home(const Location &loc);
void set_home(const Location &loc) override;
// returns the inertial navigation origin in lat/lon/alt
bool get_origin(Location &ret) const;
bool have_inertial_nav(void) const;
bool have_inertial_nav() const override;
bool get_velocity_NED(Vector3f &vec) const;
bool get_velocity_NED(Vector3f &vec) const override;
// return the relative position NED to either home or origin
// return true if the estimate is valid
@ -159,10 +159,10 @@ public:
void set_ekf_use(bool setting);
// is the AHRS subsystem healthy?
bool healthy(void) const;
bool healthy() const override;
// true if the AHRS has completed initialisation
bool initialised(void) const;
bool initialised() const override;
// get_filter_status - returns filter status as a series of flags
bool get_filter_status(nav_filter_status &status) const;
@ -176,26 +176,26 @@ public:
// return the amount of yaw angle change due to the last yaw angle reset in radians
// returns the time of the last yaw angle reset or 0 if no reset has ever occurred
uint32_t getLastYawResetAngle(float &yawAng) const;
uint32_t getLastYawResetAngle(float &yawAng) const override;
// return the amount of NE position change in meters due to the last reset
// returns the time of the last reset or 0 if no reset has ever occurred
uint32_t getLastPosNorthEastReset(Vector2f &pos) const;
uint32_t getLastPosNorthEastReset(Vector2f &pos) const override;
// return the amount of NE velocity change in meters/sec due to the last reset
// returns the time of the last reset or 0 if no reset has ever occurred
uint32_t getLastVelNorthEastReset(Vector2f &vel) const;
uint32_t getLastVelNorthEastReset(Vector2f &vel) const override;
// return the amount of vertical position change due to the last reset in meters
// returns the time of the last reset or 0 if no reset has ever occurred
uint32_t getLastPosDownReset(float &posDelta) const;
uint32_t getLastPosDownReset(float &posDelta) const override;
// Resets the baro so that it reads zero at the current height
// Resets the EKF height to zero
// Adjusts the EKf origin height so that the EKF height + origin height is the same as before
// Returns true if the height datum reset has been performed
// If using a range finder for height no reset is performed and it returns false
bool resetHeightDatum(void);
bool resetHeightDatum() override;
// send a EKF_STATUS_REPORT for current EKF
void send_ekf_status_report(mavlink_channel_t chan);
@ -219,7 +219,7 @@ public:
bool get_mag_field_NED(Vector3f& ret) const;
// returns the estimated magnetic field offsets in body frame
bool get_mag_field_correction(Vector3f &ret) const;
bool get_mag_field_correction(Vector3f &ret) const override;
void setTakeoffExpected(bool val);
void setTouchdownExpected(bool val);