AP_InertialSensor: make get_delta_time() const
allows use from AP_NavEKF
This commit is contained in:
parent
95c5aeaa43
commit
b1c5f23bbd
@ -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
|
||||
|
@ -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;
|
||||
}
|
||||
|
@ -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);
|
||||
|
||||
|
@ -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;
|
||||
}
|
||||
|
||||
|
@ -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);
|
||||
|
@ -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;
|
||||
}
|
||||
|
@ -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);
|
||||
|
||||
|
@ -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;
|
||||
|
@ -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; }
|
||||
|
@ -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;
|
||||
}
|
||||
|
||||
|
@ -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
|
||||
|
@ -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;
|
||||
}
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user