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.
Delta angle calculation is now unified, so there is no need for such a method.
That also avoids developers thinking they need that method being called
somewhere in their new drivers.
The delta velocity calculation is now unified, so there is no need for such a
method. That also avoids delevopers thinking they need that method being called
somewhere in their new drivers.
Add an AuxiliaryBus class that can be derived for specific
implementations in inertial sensor backends. It's an abstract
implementation so other libraries can use the auxiliary bus exported. In
order for this to succeed the backend implementation must split the
initialization of the sensor from the actual sample collecting, like is
done in MPU6000.
When AP_InertialSensor::get_auxiliary_bus() is called it will execute
following steps:
a) Force the backends to be detected if it's the first time it's
being called
b) Find the backend identified by the id
c) call get_auxiliary_bus() on the backend so other libraries can
that AuxiliaryBus to initialize a slave device
Slave devices can be used by calling AuxiliaryBus::request_next_slave()
and are owned by the caller until AuxiliaryBus::register_periodic_read()
is called. From that time on the AuxiliaryBus object takes its ownership.
This way it's possible to do the necessary cleanup later without
introducing refcounts, that we don't have support to.
Between these 2 functions the caller can configure the slave device by
doing its specific initializations by calling the passthrough_*
functions. After the initial configuration and register_periodic_read()
is called only read() can be called.
Identify backend with an id, allowing other libraries to connect to
them. This is different from the _product_id member because it
identifies the sensor, not the board the sensor is in, which is
meaningless for our use case.
This allows backends to have a separate detection and initialization
logic. It doesn't change any backend yet and with the current code
there's no change in behavior either. This only allows
AP_InertialSensor::_detect_backend() to be called earlier so
AP_InertialSensor object can be used by other libraries. If it's not
called, later on AP_InertialSensor::init() will detect and start all
backends.
The calibration on LSM9DS0 was giving offsets between 4.0 and 4.2 on x-axis and
around 3.6 on y-axis. It turned out that those offsets were actually right.
The maximum absolute values of calibration offset should be a sensor
characteristic rather than a constant value for all sensors.
The constant value previously used (3.5 m/s/s for all axes) is set here as a
default maximum absolute calibration offset for every instance to keep it
working.
This converts the MPU6000 driver to a frontend/backend structure, and
disables all other drivers. They will be progressively re-enabled as
each is converted