mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_InertialSensor: identify backend with ID
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 commit is contained in:
parent
22c787058e
commit
7d9579c5d8
@ -1,5 +1,7 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <assert.h>
|
||||
|
||||
#include <AP_Progmem/AP_Progmem.h>
|
||||
#include "AP_InertialSensor.h"
|
||||
|
||||
@ -388,6 +390,23 @@ void AP_InertialSensor::_start_backends()
|
||||
}
|
||||
}
|
||||
|
||||
/* Find a backend that has already been succesfully detected */
|
||||
AP_InertialSensor_Backend *AP_InertialSensor::_find_backend(int16_t backend_id)
|
||||
{
|
||||
assert(_backends_detected);
|
||||
|
||||
for (uint8_t i = 0; i < _backend_count; i++) {
|
||||
int16_t id = _backends[i]->get_id();
|
||||
|
||||
if (id < 0 || id != backend_id)
|
||||
continue;
|
||||
|
||||
return _backends[i];
|
||||
}
|
||||
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
void
|
||||
AP_InertialSensor::init( Start_style style,
|
||||
Sample_rate sample_rate)
|
||||
|
@ -244,6 +244,7 @@ private:
|
||||
void _add_backend(AP_InertialSensor_Backend *backend);
|
||||
void _detect_backends(void);
|
||||
void _start_backends();
|
||||
AP_InertialSensor_Backend *_find_backend(int16_t backend_id);
|
||||
|
||||
// gyro initialisation
|
||||
void _init_gyro();
|
||||
|
@ -63,6 +63,8 @@ public:
|
||||
*/
|
||||
int16_t product_id(void) const { return _product_id; }
|
||||
|
||||
int16_t get_id() const { return _id; }
|
||||
|
||||
protected:
|
||||
// access to frontend
|
||||
AP_InertialSensor &_imu;
|
||||
@ -94,6 +96,9 @@ protected:
|
||||
// backend should fill in its product ID from AP_PRODUCT_ID_*
|
||||
int16_t _product_id;
|
||||
|
||||
// backend unique identifier or -1 if backend doesn't identify itself
|
||||
int16_t _id = -1;
|
||||
|
||||
// return the default filter frequency in Hz for the sample rate
|
||||
uint8_t _accel_filter_cutoff(void) const { return _imu._accel_filter_cutoff; }
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user