From b1c5f23bbd210f6c93b7e52ad601876666057a7e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 3 Jan 2014 11:46:24 +1100 Subject: [PATCH] AP_InertialSensor: make get_delta_time() const allows use from AP_NavEKF --- libraries/AP_InertialSensor/AP_InertialSensor.h | 2 +- libraries/AP_InertialSensor/AP_InertialSensor_Flymaple.cpp | 2 +- libraries/AP_InertialSensor/AP_InertialSensor_Flymaple.h | 2 +- libraries/AP_InertialSensor/AP_InertialSensor_HIL.cpp | 2 +- libraries/AP_InertialSensor/AP_InertialSensor_HIL.h | 2 +- libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp | 2 +- libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.h | 2 +- libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp | 2 +- libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h | 2 +- libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp | 2 +- libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.h | 2 +- libraries/AP_InertialSensor/AP_InertialSensor_PX4.cpp | 2 +- libraries/AP_InertialSensor/AP_InertialSensor_PX4.h | 2 +- 13 files changed, 13 insertions(+), 13 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.h b/libraries/AP_InertialSensor/AP_InertialSensor.h index 4530eb1e96..590e286614 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor.h @@ -135,7 +135,7 @@ public: /* get_delta_time returns the time period in seconds * overwhich the sensor data was collected */ - virtual float get_delta_time() = 0; + virtual float get_delta_time() const = 0; // return the maximum gyro drift rate in radians/s/s. This // depends on what gyro chips are being used diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Flymaple.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Flymaple.cpp index a19d9f293d..a04d9698ec 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Flymaple.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Flymaple.cpp @@ -224,7 +224,7 @@ bool AP_InertialSensor_Flymaple::update(void) return true; } -float AP_InertialSensor_Flymaple::get_delta_time(void) +float AP_InertialSensor_Flymaple::get_delta_time(void) const { return _delta_time; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Flymaple.h b/libraries/AP_InertialSensor/AP_InertialSensor_Flymaple.h index 8c247a3f30..2d546b06ac 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Flymaple.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Flymaple.h @@ -19,7 +19,7 @@ public: /* Concrete implementation of AP_InertialSensor functions: */ bool update(); - float get_delta_time(); + float get_delta_time() const; float get_gyro_drift_rate(); bool wait_for_sample(uint16_t timeout_ms); diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_HIL.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_HIL.cpp index b520bc454a..b3996dd50c 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_HIL.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_HIL.cpp @@ -32,7 +32,7 @@ bool AP_InertialSensor_HIL::update( void ) { return true; } -float AP_InertialSensor_HIL::get_delta_time() { +float AP_InertialSensor_HIL::get_delta_time() const { return _delta_time_usec * 1.0e-6; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_HIL.h b/libraries/AP_InertialSensor/AP_InertialSensor_HIL.h index f97eda8881..3b5585a0e9 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_HIL.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_HIL.h @@ -14,7 +14,7 @@ public: /* Concrete implementation of AP_InertialSensor functions: */ bool update(); - float get_delta_time(); + float get_delta_time() const; float get_gyro_drift_rate(); bool wait_for_sample(uint16_t timeout_ms); void set_accel(const Vector3f &accel); diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp index e34bd4561e..bbadc4d604 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp @@ -270,7 +270,7 @@ bool AP_InertialSensor_L3G4200D::update(void) return true; } -float AP_InertialSensor_L3G4200D::get_delta_time(void) +float AP_InertialSensor_L3G4200D::get_delta_time(void) const { return _sample_period_usec * 1.0e-6f; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.h b/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.h index 978a415009..a0350c9912 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.h @@ -19,7 +19,7 @@ public: /* Concrete implementation of AP_InertialSensor functions: */ bool update(); - float get_delta_time(); + float get_delta_time() const; float get_gyro_drift_rate(); bool wait_for_sample(uint16_t timeout_ms); diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index 8e518d565e..afa5d97c4a 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -588,7 +588,7 @@ void AP_InertialSensor_MPU6000::_dump_registers(void) // get_delta_time returns the time period in seconds overwhich the sensor data was collected -float AP_InertialSensor_MPU6000::get_delta_time() +float AP_InertialSensor_MPU6000::get_delta_time() const { // the sensor runs at 200Hz return 0.005 * _num_samples; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h index 56af873e11..3a5f0933a6 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h @@ -28,7 +28,7 @@ public: bool wait_for_sample(uint16_t timeout_ms); // get_delta_time returns the time period in seconds overwhich the sensor data was collected - float get_delta_time(); + float get_delta_time() const; uint16_t error_count(void) const { return _error_count; } bool healthy(void) const { return _error_count <= 4; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp index eed8a82df1..55fd0f1a66 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.cpp @@ -112,7 +112,7 @@ bool AP_InertialSensor_Oilpan::update() return true; } -float AP_InertialSensor_Oilpan::get_delta_time() { +float AP_InertialSensor_Oilpan::get_delta_time() const { return _delta_time_micros * 1.0e-6; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.h b/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.h index f8be696381..bffb4f2114 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Oilpan.h @@ -17,7 +17,7 @@ public: /* Concrete implementation of AP_InertialSensor functions: */ bool update(); - float get_delta_time(); // get_delta_time returns the time period in seconds overwhich the sensor data was collected + float get_delta_time() const; float get_gyro_drift_rate(); // wait for a sample to be available, with timeout in milliseconds diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_PX4.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_PX4.cpp index 2917d1342f..56cae2e1f3 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_PX4.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_PX4.cpp @@ -171,7 +171,7 @@ bool AP_InertialSensor_PX4::update(void) return true; } -float AP_InertialSensor_PX4::get_delta_time(void) +float AP_InertialSensor_PX4::get_delta_time(void) const { return _sample_time_usec * 1.0e-6f; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_PX4.h b/libraries/AP_InertialSensor/AP_InertialSensor_PX4.h index 1af9f9c697..e37806f660 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_PX4.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_PX4.h @@ -26,7 +26,7 @@ public: /* Concrete implementation of AP_InertialSensor functions: */ bool update(); - float get_delta_time(); + float get_delta_time() const; float get_gyro_drift_rate(); bool wait_for_sample(uint16_t timeout_ms); bool healthy(void) const;