2014-10-14 01:48:33 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
/*
|
2014-10-15 23:31:21 -03:00
|
|
|
IMU driver backend class. Each supported gyro/accel sensor type
|
|
|
|
needs to have an object derived from this class.
|
|
|
|
|
|
|
|
Note that drivers can implement just gyros or just accels, and can
|
|
|
|
also provide multiple gyro/accel instances.
|
2014-10-14 01:48:33 -03:00
|
|
|
*/
|
2016-01-19 21:26:31 -04:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <inttypes.h>
|
|
|
|
|
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
|
|
|
|
#include "AP_InertialSensor.h"
|
2014-10-14 01:48:33 -03:00
|
|
|
|
2015-08-05 13:36:14 -03:00
|
|
|
class AuxiliaryBus;
|
2016-01-19 21:26:31 -04:00
|
|
|
class DataFlash_Class;
|
2015-08-05 13:36:14 -03:00
|
|
|
|
2014-10-14 01:48:33 -03:00
|
|
|
class AP_InertialSensor_Backend
|
|
|
|
{
|
|
|
|
public:
|
2014-10-15 05:54:30 -03:00
|
|
|
AP_InertialSensor_Backend(AP_InertialSensor &imu);
|
2015-10-01 20:04:04 -03:00
|
|
|
AP_InertialSensor_Backend(const AP_InertialSensor_Backend &that) = delete;
|
2014-10-14 01:48:33 -03:00
|
|
|
|
|
|
|
// we declare a virtual destructor so that drivers can
|
|
|
|
// override with a custom destructor if need be.
|
|
|
|
virtual ~AP_InertialSensor_Backend(void) {}
|
|
|
|
|
2016-01-19 21:26:31 -04:00
|
|
|
/*
|
2014-10-14 01:48:33 -03:00
|
|
|
* Update the sensor data. Called by the frontend to transfer
|
2014-10-15 20:32:40 -03:00
|
|
|
* accumulated sensor readings to the frontend structure via the
|
2015-02-17 02:50:59 -04:00
|
|
|
* _publish_gyro() and _publish_accel() functions
|
2014-10-14 01:48:33 -03:00
|
|
|
*/
|
|
|
|
virtual bool update() = 0;
|
|
|
|
|
2015-11-15 20:38:43 -04:00
|
|
|
/*
|
|
|
|
* optional function to accumulate more samples. This is needed for drivers that don't use a timer to gather samples
|
2014-10-14 01:48:33 -03:00
|
|
|
*/
|
2015-11-15 20:38:43 -04:00
|
|
|
virtual void accumulate() {}
|
2014-10-14 01:48:33 -03:00
|
|
|
|
2015-08-05 10:01:52 -03:00
|
|
|
/*
|
|
|
|
* Configure and start all sensors. The empty implementation allows
|
|
|
|
* subclasses to already start the sensors when it's detected
|
|
|
|
*/
|
|
|
|
virtual void start() { }
|
|
|
|
|
2015-08-05 13:36:14 -03:00
|
|
|
/*
|
|
|
|
* Return an AuxiliaryBus if backend has another bus it is able to export
|
|
|
|
*/
|
2015-10-02 15:02:16 -03:00
|
|
|
virtual AuxiliaryBus *get_auxiliary_bus() { return nullptr; }
|
2015-08-05 13:36:14 -03:00
|
|
|
|
2014-10-15 23:14:56 -03:00
|
|
|
/*
|
|
|
|
return the product ID
|
|
|
|
*/
|
|
|
|
int16_t product_id(void) const { return _product_id; }
|
|
|
|
|
2015-08-16 16:16:11 -03:00
|
|
|
int16_t get_id() const { return _id; }
|
|
|
|
|
2014-10-14 01:48:33 -03:00
|
|
|
protected:
|
2014-10-15 20:32:40 -03:00
|
|
|
// access to frontend
|
|
|
|
AP_InertialSensor &_imu;
|
2014-10-14 01:48:33 -03:00
|
|
|
|
2015-02-17 02:54:17 -04:00
|
|
|
void _rotate_and_correct_accel(uint8_t instance, Vector3f &accel);
|
|
|
|
void _rotate_and_correct_gyro(uint8_t instance, Vector3f &gyro);
|
|
|
|
|
2015-02-17 02:50:59 -04:00
|
|
|
// rotate gyro vector, offset and publish
|
2015-08-28 12:18:09 -03:00
|
|
|
void _publish_gyro(uint8_t instance, const Vector3f &gyro);
|
2015-02-17 02:50:59 -04:00
|
|
|
|
2015-09-08 14:05:37 -03:00
|
|
|
// this should be called every time a new gyro raw sample is available -
|
|
|
|
// be it published or not
|
|
|
|
// the sample is raw in the sense that it's not filtered yet, but it must
|
|
|
|
// be rotated and corrected (_rotate_and_correct_gyro)
|
2015-11-15 20:58:08 -04:00
|
|
|
void _notify_new_gyro_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0);
|
2015-09-08 14:05:37 -03:00
|
|
|
|
2015-02-17 02:50:59 -04:00
|
|
|
// rotate accel vector, scale, offset and publish
|
2015-08-28 12:18:09 -03:00
|
|
|
void _publish_accel(uint8_t instance, const Vector3f &accel);
|
2014-10-14 01:48:33 -03:00
|
|
|
|
2015-08-27 16:05:13 -03:00
|
|
|
// this should be called every time a new accel raw sample is available -
|
|
|
|
// be it published or not
|
|
|
|
// the sample is raw in the sense that it's not filtered yet, but it must
|
|
|
|
// be rotated and corrected (_rotate_and_correct_accel)
|
2016-08-31 01:56:27 -03:00
|
|
|
void _notify_new_accel_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0, bool fsync_set=false);
|
2015-08-27 16:05:13 -03:00
|
|
|
|
2015-06-09 17:47:16 -03:00
|
|
|
// set accelerometer max absolute offset for calibration
|
2015-06-29 21:51:43 -03:00
|
|
|
void _set_accel_max_abs_offset(uint8_t instance, float offset);
|
2015-06-09 17:47:16 -03:00
|
|
|
|
2015-11-15 20:05:20 -04:00
|
|
|
// get accelerometer raw sample rate
|
AP_InertialSensor: use raw sample rate terminology
In order to avoid confusion between sample rate from sensor and sample rate
from the frontend class (AP_InertialSensor), use "raw sample rate" to refer to
the former.
The changes in the code were basically done with the following commands:
git grep -wl _accel_sample_rates | xargs sed -i "s,\<_accel_sample_rates\>,_accel_raw_sample_rates,g"
git grep -wl _set_accel_sample_rate | xargs sed -i "s,\<_set_accel_sample_rate\>,_set_accel_raw_sample_rate,g"
git grep -wl _accel_sample_rate | xargs sed -i "s,\<_accel_sample_rate\>,_accel_raw_sample_rate,g"
git grep -wl _gyro_sample_rates | xargs sed -i "s,\<_gyro_sample_rates\>,_gyro_raw_sample_rates,g"
git grep -wl _set_gyro_sample_rate | xargs sed -i "s,\<_set_gyro_sample_rate\>,_set_gyro_raw_sample_rate,g"
git grep -wl _gyro_sample_rate | xargs sed -i "s,\<_gyro_sample_rate\>,_gyro_raw_sample_rate,g"
And also with minor changes on indentation and comments.
2015-09-10 09:56:28 -03:00
|
|
|
uint32_t _accel_raw_sample_rate(uint8_t instance) const {
|
|
|
|
return _imu._accel_raw_sample_rates[instance];
|
2015-08-03 16:22:41 -03:00
|
|
|
}
|
|
|
|
|
2015-11-15 20:05:20 -04:00
|
|
|
// get gyroscope raw sample rate
|
AP_InertialSensor: use raw sample rate terminology
In order to avoid confusion between sample rate from sensor and sample rate
from the frontend class (AP_InertialSensor), use "raw sample rate" to refer to
the former.
The changes in the code were basically done with the following commands:
git grep -wl _accel_sample_rates | xargs sed -i "s,\<_accel_sample_rates\>,_accel_raw_sample_rates,g"
git grep -wl _set_accel_sample_rate | xargs sed -i "s,\<_set_accel_sample_rate\>,_set_accel_raw_sample_rate,g"
git grep -wl _accel_sample_rate | xargs sed -i "s,\<_accel_sample_rate\>,_accel_raw_sample_rate,g"
git grep -wl _gyro_sample_rates | xargs sed -i "s,\<_gyro_sample_rates\>,_gyro_raw_sample_rates,g"
git grep -wl _set_gyro_sample_rate | xargs sed -i "s,\<_set_gyro_sample_rate\>,_set_gyro_raw_sample_rate,g"
git grep -wl _gyro_sample_rate | xargs sed -i "s,\<_gyro_sample_rate\>,_gyro_raw_sample_rate,g"
And also with minor changes on indentation and comments.
2015-09-10 09:56:28 -03:00
|
|
|
uint32_t _gyro_raw_sample_rate(uint8_t instance) const {
|
|
|
|
return _imu._gyro_raw_sample_rates[instance];
|
2015-09-10 08:56:34 -03:00
|
|
|
}
|
|
|
|
|
2015-03-16 23:32:54 -03:00
|
|
|
// publish a temperature value
|
|
|
|
void _publish_temperature(uint8_t instance, float temperature);
|
|
|
|
|
2014-12-29 06:19:35 -04:00
|
|
|
// set accelerometer error_count
|
|
|
|
void _set_accel_error_count(uint8_t instance, uint32_t error_count);
|
|
|
|
|
|
|
|
// set gyro error_count
|
|
|
|
void _set_gyro_error_count(uint8_t instance, uint32_t error_count);
|
|
|
|
|
2014-10-15 23:14:56 -03:00
|
|
|
// backend should fill in its product ID from AP_PRODUCT_ID_*
|
|
|
|
int16_t _product_id;
|
|
|
|
|
2015-08-16 16:16:11 -03:00
|
|
|
// backend unique identifier or -1 if backend doesn't identify itself
|
|
|
|
int16_t _id = -1;
|
|
|
|
|
2014-10-16 17:52:21 -03:00
|
|
|
// return the default filter frequency in Hz for the sample rate
|
2015-03-11 21:58:36 -03:00
|
|
|
uint8_t _accel_filter_cutoff(void) const { return _imu._accel_filter_cutoff; }
|
|
|
|
|
|
|
|
// return the default filter frequency in Hz for the sample rate
|
|
|
|
uint8_t _gyro_filter_cutoff(void) const { return _imu._gyro_filter_cutoff; }
|
2014-10-16 17:52:21 -03:00
|
|
|
|
2015-03-11 20:02:36 -03:00
|
|
|
// return the requested sample rate in Hz
|
|
|
|
uint16_t get_sample_rate_hz(void) const;
|
|
|
|
|
2015-05-06 23:08:30 -03:00
|
|
|
// access to frontend dataflash
|
2016-01-19 21:26:31 -04:00
|
|
|
DataFlash_Class *get_dataflash(void) const {
|
|
|
|
return _imu._log_raw_data? _imu._dataflash : NULL;
|
2015-05-06 23:08:30 -03:00
|
|
|
}
|
|
|
|
|
2015-11-15 20:05:20 -04:00
|
|
|
// common gyro update function for all backends
|
|
|
|
void update_gyro(uint8_t instance);
|
|
|
|
|
|
|
|
// common accel update function for all backends
|
|
|
|
void update_accel(uint8_t instance);
|
2016-01-19 21:26:31 -04:00
|
|
|
|
2015-11-15 20:05:20 -04:00
|
|
|
// support for updating filter at runtime
|
2015-11-16 02:31:15 -04:00
|
|
|
int8_t _last_accel_filter_hz[INS_MAX_INSTANCES];
|
|
|
|
int8_t _last_gyro_filter_hz[INS_MAX_INSTANCES];
|
2016-01-19 21:26:31 -04:00
|
|
|
|
2014-10-15 20:32:40 -03:00
|
|
|
// note that each backend is also expected to have a static detect()
|
2014-10-14 01:48:33 -03:00
|
|
|
// function which instantiates an instance of the backend sensor
|
2014-10-15 20:32:40 -03:00
|
|
|
// driver if the sensor is available
|
2014-10-14 01:48:33 -03:00
|
|
|
};
|