mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
AP_InertialSensor: remove unused get_last_sample_time_micros()
This commit is contained in:
parent
b8f1289fce
commit
a04c056598
@ -227,11 +227,6 @@ float AP_InertialSensor_Flymaple::get_delta_time(void)
|
|||||||
return _delta_time;
|
return _delta_time;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t AP_InertialSensor_Flymaple::get_last_sample_time_micros(void)
|
|
||||||
{
|
|
||||||
return _last_update_usec;
|
|
||||||
}
|
|
||||||
|
|
||||||
float AP_InertialSensor_Flymaple::get_gyro_drift_rate(void)
|
float AP_InertialSensor_Flymaple::get_gyro_drift_rate(void)
|
||||||
{
|
{
|
||||||
// Dont really know this for the ITG-3200.
|
// Dont really know this for the ITG-3200.
|
||||||
|
@ -20,7 +20,6 @@ public:
|
|||||||
/* Concrete implementation of AP_InertialSensor functions: */
|
/* Concrete implementation of AP_InertialSensor functions: */
|
||||||
bool update();
|
bool update();
|
||||||
float get_delta_time();
|
float get_delta_time();
|
||||||
uint32_t get_last_sample_time_micros();
|
|
||||||
float get_gyro_drift_rate();
|
float get_gyro_drift_rate();
|
||||||
bool sample_available();
|
bool sample_available();
|
||||||
bool wait_for_sample(uint16_t timeout_ms);
|
bool wait_for_sample(uint16_t timeout_ms);
|
||||||
|
@ -37,9 +37,7 @@ bool AP_InertialSensor_HIL::update( void ) {
|
|||||||
float AP_InertialSensor_HIL::get_delta_time() {
|
float AP_InertialSensor_HIL::get_delta_time() {
|
||||||
return _delta_time_usec * 1.0e-6;
|
return _delta_time_usec * 1.0e-6;
|
||||||
}
|
}
|
||||||
uint32_t AP_InertialSensor_HIL::get_last_sample_time_micros() {
|
|
||||||
return _last_update_ms * 1000;
|
|
||||||
}
|
|
||||||
float AP_InertialSensor_HIL::get_gyro_drift_rate(void) {
|
float AP_InertialSensor_HIL::get_gyro_drift_rate(void) {
|
||||||
// 0.5 degrees/second/minute
|
// 0.5 degrees/second/minute
|
||||||
return ToRad(0.5/60);
|
return ToRad(0.5/60);
|
||||||
|
@ -15,7 +15,6 @@ public:
|
|||||||
/* Concrete implementation of AP_InertialSensor functions: */
|
/* Concrete implementation of AP_InertialSensor functions: */
|
||||||
bool update();
|
bool update();
|
||||||
float get_delta_time();
|
float get_delta_time();
|
||||||
uint32_t get_last_sample_time_micros();
|
|
||||||
float get_gyro_drift_rate();
|
float get_gyro_drift_rate();
|
||||||
bool sample_available();
|
bool sample_available();
|
||||||
bool wait_for_sample(uint16_t timeout_ms);
|
bool wait_for_sample(uint16_t timeout_ms);
|
||||||
|
@ -18,7 +18,6 @@ public:
|
|||||||
/* Concrete implementation of AP_InertialSensor functions: */
|
/* Concrete implementation of AP_InertialSensor functions: */
|
||||||
bool update();
|
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(); // get_delta_time returns the time period in seconds overwhich the sensor data was collected
|
||||||
//uint32_t get_last_sample_time_micros(); // last_sample_time - get time (in microseconds) that last sample was captured
|
|
||||||
float get_gyro_drift_rate();
|
float get_gyro_drift_rate();
|
||||||
|
|
||||||
// sample_available() - true when a new sample is available
|
// sample_available() - true when a new sample is available
|
||||||
|
Loading…
Reference in New Issue
Block a user