mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: removed axis getters for accel/gyro
these were only being used in one place, and in that place were used incorrectly!
This commit is contained in:
parent
453f879330
commit
dfc252a78d
|
@ -105,21 +105,6 @@ public:
|
||||||
// check if the sensors have new data
|
// check if the sensors have new data
|
||||||
virtual bool new_data_available(void) = 0;
|
virtual bool new_data_available(void) = 0;
|
||||||
|
|
||||||
/* Getters for individual gyro axes.
|
|
||||||
* Gyros have correct coordinate frame and units (degrees per second).
|
|
||||||
*/
|
|
||||||
virtual float gx() = 0;
|
|
||||||
virtual float gy() = 0;
|
|
||||||
virtual float gz() = 0;
|
|
||||||
|
|
||||||
/* Getters for individual accel axes.
|
|
||||||
* Accels have correct coordinate frame ( flat level ax, ay = 0; az = -9.81)
|
|
||||||
* and units (meters per second squared).
|
|
||||||
*/
|
|
||||||
virtual float ax() = 0;
|
|
||||||
virtual float ay() = 0;
|
|
||||||
virtual float az() = 0;
|
|
||||||
|
|
||||||
/* Temperature, in degrees celsius, of the gyro. */
|
/* Temperature, in degrees celsius, of the gyro. */
|
||||||
virtual float temperature() = 0;
|
virtual float temperature() = 0;
|
||||||
|
|
||||||
|
|
|
@ -279,26 +279,6 @@ bool AP_InertialSensor_MPU6000::new_data_available( void )
|
||||||
return _count != 0;
|
return _count != 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
float AP_InertialSensor_MPU6000::gx() {
|
|
||||||
return _gyro.x;
|
|
||||||
}
|
|
||||||
float AP_InertialSensor_MPU6000::gy() {
|
|
||||||
return _gyro.y;
|
|
||||||
}
|
|
||||||
float AP_InertialSensor_MPU6000::gz() {
|
|
||||||
return _gyro.z;
|
|
||||||
}
|
|
||||||
|
|
||||||
float AP_InertialSensor_MPU6000::ax() {
|
|
||||||
return _accel.x;
|
|
||||||
}
|
|
||||||
float AP_InertialSensor_MPU6000::ay() {
|
|
||||||
return _accel.y;
|
|
||||||
}
|
|
||||||
float AP_InertialSensor_MPU6000::az() {
|
|
||||||
return _accel.z;
|
|
||||||
}
|
|
||||||
|
|
||||||
float AP_InertialSensor_MPU6000::temperature() {
|
float AP_InertialSensor_MPU6000::temperature() {
|
||||||
return _temp;
|
return _temp;
|
||||||
}
|
}
|
||||||
|
|
|
@ -28,12 +28,6 @@ public:
|
||||||
/* Concrete implementation of AP_InertialSensor functions: */
|
/* Concrete implementation of AP_InertialSensor functions: */
|
||||||
bool update();
|
bool update();
|
||||||
bool new_data_available();
|
bool new_data_available();
|
||||||
float gx();
|
|
||||||
float gy();
|
|
||||||
float gz();
|
|
||||||
float ax();
|
|
||||||
float ay();
|
|
||||||
float az();
|
|
||||||
float temperature();
|
float temperature();
|
||||||
float get_gyro_drift_rate();
|
float get_gyro_drift_rate();
|
||||||
|
|
||||||
|
|
|
@ -101,27 +101,6 @@ bool AP_InertialSensor_Oilpan::new_data_available( void )
|
||||||
return _adc->new_data_available(_sensors);
|
return _adc->new_data_available(_sensors);
|
||||||
}
|
}
|
||||||
|
|
||||||
float AP_InertialSensor_Oilpan::gx() {
|
|
||||||
return _gyro.x;
|
|
||||||
}
|
|
||||||
float AP_InertialSensor_Oilpan::gy() {
|
|
||||||
return _gyro.y;
|
|
||||||
}
|
|
||||||
float AP_InertialSensor_Oilpan::gz() {
|
|
||||||
return _gyro.z;
|
|
||||||
}
|
|
||||||
|
|
||||||
float AP_InertialSensor_Oilpan::ax() {
|
|
||||||
return _accel.x;
|
|
||||||
}
|
|
||||||
float AP_InertialSensor_Oilpan::ay() {
|
|
||||||
return _accel.y;
|
|
||||||
}
|
|
||||||
float AP_InertialSensor_Oilpan::az() {
|
|
||||||
return _accel.z;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
float AP_InertialSensor_Oilpan::temperature() {
|
float AP_InertialSensor_Oilpan::temperature() {
|
||||||
return _temp;
|
return _temp;
|
||||||
}
|
}
|
||||||
|
|
|
@ -19,12 +19,6 @@ public:
|
||||||
/* Concrete implementation of AP_InertialSensor functions: */
|
/* Concrete implementation of AP_InertialSensor functions: */
|
||||||
bool update();
|
bool update();
|
||||||
bool new_data_available();
|
bool new_data_available();
|
||||||
float gx();
|
|
||||||
float gy();
|
|
||||||
float gz();
|
|
||||||
float ax();
|
|
||||||
float ay();
|
|
||||||
float az();
|
|
||||||
float temperature();
|
float temperature();
|
||||||
uint32_t get_delta_time_micros(); // get_delta_time returns the time period in seconds overwhich the sensor data was collected
|
uint32_t get_delta_time_micros(); // 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
|
//uint32_t get_last_sample_time_micros(); // last_sample_time - get time (in microseconds) that last sample was captured
|
||||||
|
|
|
@ -31,26 +31,6 @@ bool AP_InertialSensor_Stub::new_data_available( void ) {
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
float AP_InertialSensor_Stub::gx() {
|
|
||||||
return 0.0f;
|
|
||||||
}
|
|
||||||
float AP_InertialSensor_Stub::gy() {
|
|
||||||
return 0.0f;
|
|
||||||
}
|
|
||||||
float AP_InertialSensor_Stub::gz() {
|
|
||||||
return 0.0f;
|
|
||||||
}
|
|
||||||
|
|
||||||
float AP_InertialSensor_Stub::ax() {
|
|
||||||
return 0.0f;
|
|
||||||
}
|
|
||||||
float AP_InertialSensor_Stub::ay() {
|
|
||||||
return 0.0f;
|
|
||||||
}
|
|
||||||
float AP_InertialSensor_Stub::az() {
|
|
||||||
return 0.0f;
|
|
||||||
}
|
|
||||||
|
|
||||||
float AP_InertialSensor_Stub::temperature() {
|
float AP_InertialSensor_Stub::temperature() {
|
||||||
return 0.0;
|
return 0.0;
|
||||||
}
|
}
|
||||||
|
|
|
@ -19,12 +19,6 @@ public:
|
||||||
/* Concrete implementation of AP_InertialSensor functions: */
|
/* Concrete implementation of AP_InertialSensor functions: */
|
||||||
bool update();
|
bool update();
|
||||||
bool new_data_available();
|
bool new_data_available();
|
||||||
float gx();
|
|
||||||
float gy();
|
|
||||||
float gz();
|
|
||||||
float ax();
|
|
||||||
float ay();
|
|
||||||
float az();
|
|
||||||
float temperature();
|
float temperature();
|
||||||
uint32_t get_delta_time_micros();
|
uint32_t get_delta_time_micros();
|
||||||
uint32_t get_last_sample_time_micros();
|
uint32_t get_last_sample_time_micros();
|
||||||
|
|
Loading…
Reference in New Issue