Browse Source

AP_InertialSensor: add override keyword

master
Peter Barker 6 years ago committed by Andrew Tridgell
parent
commit
011c93f38e
  1. 6
      libraries/AP_InertialSensor/AP_InertialSensor.h
  2. 2
      libraries/AP_InertialSensor/AP_InertialSensor_HIL.h
  3. 2
      libraries/AP_InertialSensor/AP_InertialSensor_PX4.h
  4. 2
      libraries/AP_InertialSensor/AP_InertialSensor_SITL.h

6
libraries/AP_InertialSensor/AP_InertialSensor.h

@ -562,11 +562,11 @@ private:
AccelCalibrator *_accel_calibrator; AccelCalibrator *_accel_calibrator;
//save accelerometer bias and scale factors //save accelerometer bias and scale factors
void _acal_save_calibrations(); void _acal_save_calibrations() override;
void _acal_event_failure(); void _acal_event_failure() override;
// Returns AccelCalibrator objects pointer for specified acceleromter // Returns AccelCalibrator objects pointer for specified acceleromter
AccelCalibrator* _acal_get_calibrator(uint8_t i) { return i<get_accel_count()?&(_accel_calibrator[i]):nullptr; } AccelCalibrator* _acal_get_calibrator(uint8_t i) override { return i<get_accel_count()?&(_accel_calibrator[i]):nullptr; }
float _trim_pitch; float _trim_pitch;
float _trim_roll; float _trim_roll;

2
libraries/AP_InertialSensor/AP_InertialSensor_HIL.h

@ -9,7 +9,7 @@ public:
AP_InertialSensor_HIL(AP_InertialSensor &imu); AP_InertialSensor_HIL(AP_InertialSensor &imu);
/* update accel and gyro state */ /* update accel and gyro state */
bool update(); bool update() override;
// detect the sensor // detect the sensor
static AP_InertialSensor_Backend *detect(AP_InertialSensor &imu); static AP_InertialSensor_Backend *detect(AP_InertialSensor &imu);

2
libraries/AP_InertialSensor/AP_InertialSensor_PX4.h

@ -20,7 +20,7 @@ public:
AP_InertialSensor_PX4(AP_InertialSensor &imu); AP_InertialSensor_PX4(AP_InertialSensor &imu);
/* update accel and gyro state */ /* update accel and gyro state */
bool update(); bool update() override;
// detect the sensor // detect the sensor
static AP_InertialSensor_Backend *detect(AP_InertialSensor &imu); static AP_InertialSensor_Backend *detect(AP_InertialSensor &imu);

2
libraries/AP_InertialSensor/AP_InertialSensor_SITL.h

@ -13,7 +13,7 @@ public:
AP_InertialSensor_SITL(AP_InertialSensor &imu); AP_InertialSensor_SITL(AP_InertialSensor &imu);
/* update accel and gyro state */ /* update accel and gyro state */
bool update(); bool update() override;
// detect the sensor // detect the sensor
static AP_InertialSensor_Backend *detect(AP_InertialSensor &imu); static AP_InertialSensor_Backend *detect(AP_InertialSensor &imu);

Loading…
Cancel
Save