AP_InertialSensor: simplify get_delta_time() API

use a single float return rather than two APIs.

This also changes the MPU6k driver to match the new 2.9 behaviour of
using the MPU6k sample timing instead of micros()
This commit is contained in:
Andrew Tridgell 2013-01-11 21:17:21 +11:00
parent d6ce86a746
commit 6142eac4b4
9 changed files with 17 additions and 29 deletions

View File

@ -113,8 +113,7 @@ public:
/* get_delta_time returns the time period in seconds
* overwhich the sensor data was collected
*/
virtual float get_delta_time() { return (float)get_delta_time_micros() * 1.0e-6; }
virtual uint32_t get_delta_time_micros() = 0;
virtual float get_delta_time() = 0;
// return the maximum gyro drift rate in radians/s/s. This
// depends on what gyro chips are being used

View File

@ -190,13 +190,7 @@ const uint8_t AP_InertialSensor_MPU6000::_temp_data_index = 3;
int16_t AP_InertialSensor_MPU6000::_mpu6000_product_id = AP_PRODUCT_ID_NONE;
AP_HAL::DigitalSource *AP_InertialSensor_MPU6000::_drdy_pin = NULL;
// variables to calculate time period over which a group of samples were
// collected
// time period overwhich samples were collected (initialise to non-zero
// number but will be overwritten on 2nd read in any case)
static volatile uint32_t _delta_time_micros = 1;
// time we start collecting sample (reset on update)
static volatile uint32_t _delta_time_start_micros = 0;
// time latest sample was collected
static volatile uint32_t _last_sample_time_micros = 0;
@ -304,7 +298,6 @@ void AP_InertialSensor_MPU6000::wait_for_sample()
bool AP_InertialSensor_MPU6000::update( void )
{
int32_t sum[7];
uint16_t count;
float count_scale;
Vector3f accel_scale = _accel_scale.get();
@ -320,17 +313,12 @@ bool AP_InertialSensor_MPU6000::update( void )
_sum[i] = 0;
}
count = _count;
_num_samples = _count;
_count = 0;
// record sample time
_delta_time_micros = _last_sample_time_micros
- _delta_time_start_micros;
_delta_time_start_micros = _last_sample_time_micros;
}
hal.scheduler->resume_timer_procs();
count_scale = 1.0 / count;
count_scale = 1.0 / _num_samples;
_gyro.x = _gyro_scale * _gyro_data_sign[0] * sum[_gyro_data_index[0]] * count_scale;
_gyro.y = _gyro_scale * _gyro_data_sign[1] * sum[_gyro_data_index[1]] * count_scale;
@ -659,9 +647,9 @@ void AP_InertialSensor_MPU6000::_dump_registers(void)
// get_delta_time returns the time period in seconds overwhich the sensor data was collected
uint32_t AP_InertialSensor_MPU6000::get_delta_time_micros()
float AP_InertialSensor_MPU6000::get_delta_time()
{
return _delta_time_micros;
return _msec_per_sample * 0.001 * _num_samples;
}
// Update gyro offsets with new values. Offsets provided in as scaled deg/sec values

View File

@ -45,7 +45,7 @@ public:
uint16_t num_samples_available();
// get_delta_time returns the time period in seconds overwhich the sensor data was collected
uint32_t get_delta_time_micros();
float get_delta_time();
protected:
uint16_t _init_sensor( Sample_rate sample_rate );
@ -66,7 +66,8 @@ private:
static AP_HAL::SPIDeviceDriver *_spi;
static AP_HAL::Semaphore *_spi_sem;
uint8_t _msec_per_sample;
uint8_t _msec_per_sample;
uint16_t _num_samples;
float _temp;

View File

@ -107,8 +107,8 @@ float AP_InertialSensor_Oilpan::temperature() {
return _temp;
}
uint32_t AP_InertialSensor_Oilpan::get_delta_time_micros() {
return _delta_time_micros;
float AP_InertialSensor_Oilpan::get_delta_time() {
return _delta_time_micros * 1.0e-6;
}
/* ------ Private functions -------------------------------------------*/

View File

@ -19,7 +19,7 @@ public:
bool update();
bool new_data_available();
float temperature();
uint32_t get_delta_time_micros(); // 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();

View File

@ -105,9 +105,9 @@ float AP_InertialSensor_PX4::temperature(void)
return 0.0;
}
uint32_t AP_InertialSensor_PX4::get_delta_time_micros(void)
float AP_InertialSensor_PX4::get_delta_time(void)
{
return _delta_time_usec;
return _delta_time_usec * 1.0e-6;
}
uint32_t AP_InertialSensor_PX4::get_last_sample_time_micros(void)

View File

@ -23,7 +23,7 @@ public:
bool update();
bool new_data_available();
float temperature();
uint32_t get_delta_time_micros();
float get_delta_time();
uint32_t get_last_sample_time_micros();
float get_gyro_drift_rate();
uint16_t num_samples_available();

View File

@ -35,8 +35,8 @@ bool AP_InertialSensor_Stub::new_data_available( void ) {
float AP_InertialSensor_Stub::temperature() {
return 0.0;
}
uint32_t AP_InertialSensor_Stub::get_delta_time_micros() {
return _delta_time_usec;
float AP_InertialSensor_Stub::get_delta_time() {
return _delta_time_usec * 1.0e-6;
}
uint32_t AP_InertialSensor_Stub::get_last_sample_time_micros() {
return _last_update_ms * 1000;

View File

@ -17,7 +17,7 @@ public:
bool update();
bool new_data_available();
float temperature();
uint32_t get_delta_time_micros();
float get_delta_time();
uint32_t get_last_sample_time_micros();
float get_gyro_drift_rate();
uint16_t num_samples_available();