AP_InertialSensor: removed unused new_data_available() and temperature() APIs
This commit is contained in:
parent
7b1245937c
commit
5643c371b9
@ -104,12 +104,6 @@ public:
|
||||
*/
|
||||
virtual bool update() = 0;
|
||||
|
||||
// check if the sensors have new data
|
||||
virtual bool new_data_available(void) = 0;
|
||||
|
||||
/* Temperature, in degrees celsius, of the gyro. */
|
||||
virtual float temperature() = 0;
|
||||
|
||||
/* get_delta_time returns the time period in seconds
|
||||
* overwhich the sensor data was collected
|
||||
*/
|
||||
|
@ -107,15 +107,6 @@ bool AP_InertialSensor_Oilpan::update()
|
||||
return true;
|
||||
}
|
||||
|
||||
bool AP_InertialSensor_Oilpan::new_data_available( void )
|
||||
{
|
||||
return _adc->new_data_available(_sensors);
|
||||
}
|
||||
|
||||
float AP_InertialSensor_Oilpan::temperature() {
|
||||
return _temp;
|
||||
}
|
||||
|
||||
float AP_InertialSensor_Oilpan::get_delta_time() {
|
||||
return _delta_time_micros * 1.0e-6;
|
||||
}
|
||||
|
@ -17,8 +17,6 @@ public:
|
||||
|
||||
/* Concrete implementation of AP_InertialSensor functions: */
|
||||
bool update();
|
||||
bool new_data_available();
|
||||
float temperature();
|
||||
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();
|
||||
|
@ -109,17 +109,6 @@ bool AP_InertialSensor_PX4::update(void)
|
||||
return true;
|
||||
}
|
||||
|
||||
bool AP_InertialSensor_PX4::new_data_available(void)
|
||||
{
|
||||
return num_samples_available() > 0;
|
||||
}
|
||||
|
||||
|
||||
float AP_InertialSensor_PX4::temperature(void)
|
||||
{
|
||||
return 0.0;
|
||||
}
|
||||
|
||||
float AP_InertialSensor_PX4::get_delta_time(void)
|
||||
{
|
||||
return _delta_time;
|
||||
|
@ -21,8 +21,6 @@ public:
|
||||
|
||||
/* Concrete implementation of AP_InertialSensor functions: */
|
||||
bool update();
|
||||
bool new_data_available();
|
||||
float temperature();
|
||||
float get_delta_time();
|
||||
uint32_t get_last_sample_time_micros();
|
||||
float get_gyro_drift_rate();
|
||||
|
@ -27,14 +27,7 @@ bool AP_InertialSensor_Stub::update( void ) {
|
||||
_last_update_ms = now;
|
||||
return true;
|
||||
}
|
||||
bool AP_InertialSensor_Stub::new_data_available( void ) {
|
||||
return num_samples_available() > 0;
|
||||
}
|
||||
|
||||
|
||||
float AP_InertialSensor_Stub::temperature() {
|
||||
return 0.0;
|
||||
}
|
||||
float AP_InertialSensor_Stub::get_delta_time() {
|
||||
return _delta_time_usec * 1.0e-6;
|
||||
}
|
||||
|
@ -15,8 +15,6 @@ public:
|
||||
|
||||
/* Concrete implementation of AP_InertialSensor functions: */
|
||||
bool update();
|
||||
bool new_data_available();
|
||||
float temperature();
|
||||
float get_delta_time();
|
||||
uint32_t get_last_sample_time_micros();
|
||||
float get_gyro_drift_rate();
|
||||
|
@ -169,7 +169,6 @@ void run_test()
|
||||
{
|
||||
Vector3f accel;
|
||||
Vector3f gyro;
|
||||
float temperature;
|
||||
float length;
|
||||
uint8_t counter = 0;
|
||||
|
||||
@ -191,14 +190,13 @@ void run_test()
|
||||
ins.update();
|
||||
accel = ins.get_accel();
|
||||
gyro = ins.get_gyro();
|
||||
temperature = ins.temperature();
|
||||
|
||||
length = accel.length();
|
||||
|
||||
if (counter++ % 50 == 0) {
|
||||
// display results
|
||||
hal.console->printf_P(PSTR("Accel X:%4.2f \t Y:%4.2f \t Z:%4.2f \t len:%4.2f \t Gyro X:%4.2f \t Y:%4.2f \t Z:%4.2f \t Temp:%4.2f\n"),
|
||||
accel.x, accel.y, accel.z, length, gyro.x, gyro.y, gyro.z, temperature);
|
||||
hal.console->printf_P(PSTR("Accel X:%4.2f \t Y:%4.2f \t Z:%4.2f \t len:%4.2f \t Gyro X:%4.2f \t Y:%4.2f \t Z:%4.2f\n"),
|
||||
accel.x, accel.y, accel.z, length, gyro.x, gyro.y, gyro.z);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -151,7 +151,6 @@ void run_test()
|
||||
{
|
||||
Vector3f accel;
|
||||
Vector3f gyro;
|
||||
float temperature;
|
||||
float length;
|
||||
uint8_t counter = 0;
|
||||
|
||||
@ -175,14 +174,13 @@ void run_test()
|
||||
ins.update();
|
||||
accel = ins.get_accel();
|
||||
gyro = ins.get_gyro();
|
||||
temperature = ins.temperature();
|
||||
|
||||
length = accel.length();
|
||||
|
||||
if (counter++ % 50 == 0) {
|
||||
// display results
|
||||
hal.console->printf_P(PSTR("Accel X:%4.2f \t Y:%4.2f \t Z:%4.2f \t len:%4.2f \t Gyro X:%4.2f \t Y:%4.2f \t Z:%4.2f \t Temp:%4.2f dt:%u\n"),
|
||||
accel.x, accel.y, accel.z, length, gyro.x, gyro.y, gyro.z, temperature,
|
||||
hal.console->printf_P(PSTR("Accel X:%4.2f \t Y:%4.2f \t Z:%4.2f \t len:%4.2f \t Gyro X:%4.2f \t Y:%4.2f \t Z:%4.2f \t dt:%u\n"),
|
||||
accel.x, accel.y, accel.z, length, gyro.x, gyro.y, gyro.z,
|
||||
(unsigned)(1.0e6*ins.get_delta_time()));
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user