this allows enable/disable of fast sampling per IMU, making
experimentation easier.
It also fixes the fast sampling to always average over 8 samples, and
fixes the 9250 to use the correct accumulator when not doing fast
sampling
This allows each sensor to be uniquely identified in the system by using
either the index inside the backend or for those that use the Device
interface, to use the bus type, location, and device id.
We leave 16-bit for each sensor to be able to change its own
identification in future, which allows them to be changed in an
incompatible manner forcing a re-calibration.
When we are initializing the gyro and then saving the calibration we are
also saving the calibration values for the accelerometers. Right now
this is non-problematic, but we want to check that the ID of the
accelerometer corresponds to the ID of the sensor detected. If we also
save accel calibrations we would actually override the ID of the
accelerometer.
Rename the method to _save_gyro_calibration() and save only on gyro
values.
We only leave the parameter there for backward-compatibility. However
product id on the inertial sensor is not much useful since it's only
kept for the first instance.
A better implementation per-gyro and per-accel is needed in order to
avoid problems with sensors taking the offsets configured for another
sensor.
RC_Channel: To nullptr from NULL.
AC_Fence: To nullptr from NULL.
AC_Avoidance: To nullptr from NULL.
AC_PrecLand: To nullptr from NULL.
DataFlash: To nullptr from NULL.
SITL: To nullptr from NULL.
GCS_MAVLink: To nullptr from NULL.
DataFlash: To nullptr from NULL.
AP_Compass: To nullptr from NULL.
Global: To nullptr from NULL.
Global: To nullptr from NULL.
Due to the way the headers are organized changing a single change in an
inertial sensor driver would trigger a rebuild for most of the files in
the project. Time could be saved by using ccache (since most of the
things didn't change) but we can do better, i.e. re-organize the headers
so we don't have to re-build everything.
With this patch only AP_InertialSensor/AP_InertialSensor.h is exposed to
most users. There are some corner cases to integrate with some example
code, but most of the places now depend only on this header and this
header doesn't depend on the specific backends.
Now changing a single header, e.g. AP_InertialSensor_L3G4200D.h triggers
a rebuild only of these files:
$ waf copter
'copter' finished successfully (0.000s)
Waf: Entering directory `/home/lucas/p/dronecode/ardupilot/build/minlure'
[ 80/370] Compiling libraries/AP_InertialSensor/AP_InertialSensor.cpp
[ 84/370] Compiling libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp
[310/370] Linking build/minlure/ArduCopter/libArduCopter_libs.a
[370/370] Linking build/minlure/bin/arducopter
Waf: Leaving directory `/home/lucas/p/dronecode/ardupilot/build/minlure'
This is not used by any board and has a lot of commented out code. For
example, the compass is not enabled. The comment in the beginning of
the driver says it should serve as an example, but we should rather use
a working driver as an example. If this was at least a bit simpler and
that worked in the past we could refactor it to the new I2CDevice API.
This is not the case.
new functions that get a filtered min/max accel peaks on each axis with fixed 500ms timeout:
Vector3f get_accel_peak_hold_pos()
Vector3f get_accel_peak_hold_neg()
This allows slower mechanisms, such as is_flying, to detect accel spikes which would indicate ground or object impacts. Vibe is too filtered. Independent positive and negative peaks are available
This method will be used to initialize and configure I2C backends that
have an auxiliary I2C bus that can be connected to the main I2C bus,
like MPU6000 and MPU9250.
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.
This commit basically moves delta angle calculation that was previously done in
AP_InertialSensor_PX4 to a common place. Instances must publish their gyro raw
sample rate to enable delta angle calculation.
This commit basically moves delta velocity calculation that was previously done
in AP_InertialSensor_PX4 to a common place. Instances must publish their accel
raw sample rate to enable delta velocity calculation.
We don't support HAL_CPU_CLASS <= HAL_CPU_CLASS_16 anymore. This makes
INS_MAX_INSTANCES, INS_MAX_BACKENDS and INS_VIBRATION_CHECK constant for
all supported boards.
In order to allow other libraries to use the InertialSensor we need a
way to let them to get the only instance of InertialSensor. The
conventional way to do a singleton would be to let the constructor
private and force it to be instantiated from the get_instance() method.
Here however we just call panic() on the constructor if there's already
an instance alive. This allows us to let the vehicles as is. Later we
can change it so they call the get_instance() method instead.
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.
very strict check that all axis are not vibrating much at all
new param: INS_STILL_THRESH used to be a vibration threshold for different platforms
// @Description: Threshold to tolerate vibration to determine if vehicle is motionless. This depends on the frame type and if there is a constant vibration due to motors before launch or after landing. Total motionless is about 0.05. Suggested values: Planes/rover use 0.1, multirotors use 1, tradHeli uses 5
This commit changes the way libraries headers are included in source files:
- If the header is in the same directory the source belongs to, so the
notation '#include ""' is used with the path relative to the directory
containing the source.
- If the header is outside the directory containing the source, then we use
the notation '#include <>' with the path relative to libraries folder.
Some of the advantages of such approach:
- Only one search path for libraries headers.
- OSs like Windows may have a better lookup time.
Different detect() function might need different arguments and passing a
pointer to function here is cumbersome. For example, it forces to have a
method like "detect_i2c2" rather than allowing hal.i2c2 to be passed as
parameter.