mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_InertialSensor: expose get_primary_accel() for use in AHRS
This commit is contained in:
parent
cf148fa76c
commit
2c85a7ba56
@ -107,7 +107,7 @@ public:
|
|||||||
/// @returns vector of current accelerations in m/s/s
|
/// @returns vector of current accelerations in m/s/s
|
||||||
///
|
///
|
||||||
const Vector3f &get_accel(uint8_t i) const { return _accel[i]; }
|
const Vector3f &get_accel(uint8_t i) const { return _accel[i]; }
|
||||||
const Vector3f &get_accel(void) const { return get_accel(_get_primary_accel()); }
|
const Vector3f &get_accel(void) const { return get_accel(get_primary_accel()); }
|
||||||
virtual void set_accel(uint8_t instance, const Vector3f &accel) {}
|
virtual void set_accel(uint8_t instance, const Vector3f &accel) {}
|
||||||
|
|
||||||
// multi-device interface
|
// multi-device interface
|
||||||
@ -116,16 +116,16 @@ public:
|
|||||||
virtual uint8_t get_gyro_count(void) const { return 1; };
|
virtual uint8_t get_gyro_count(void) const { return 1; };
|
||||||
|
|
||||||
virtual bool get_accel_health(uint8_t instance) const { return true; }
|
virtual bool get_accel_health(uint8_t instance) const { return true; }
|
||||||
bool get_accel_health(void) const { return get_accel_health(_get_primary_accel()); }
|
bool get_accel_health(void) const { return get_accel_health(get_primary_accel()); }
|
||||||
virtual uint8_t get_accel_count(void) const { return 1; };
|
virtual uint8_t get_accel_count(void) const { return 1; };
|
||||||
|
|
||||||
// get accel offsets in m/s/s
|
// get accel offsets in m/s/s
|
||||||
const Vector3f &get_accel_offsets(uint8_t i) const { return _accel_offset[i]; }
|
const Vector3f &get_accel_offsets(uint8_t i) const { return _accel_offset[i]; }
|
||||||
const Vector3f &get_accel_offsets(void) const { return get_accel_offsets(_get_primary_accel()); }
|
const Vector3f &get_accel_offsets(void) const { return get_accel_offsets(get_primary_accel()); }
|
||||||
|
|
||||||
// get accel scale
|
// get accel scale
|
||||||
const Vector3f &get_accel_scale(uint8_t i) const { return _accel_scale[i]; }
|
const Vector3f &get_accel_scale(uint8_t i) const { return _accel_scale[i]; }
|
||||||
const Vector3f &get_accel_scale(void) const { return get_accel_scale(_get_primary_accel()); }
|
const Vector3f &get_accel_scale(void) const { return get_accel_scale(get_primary_accel()); }
|
||||||
|
|
||||||
/* Update the sensor data, so that getters are nonblocking.
|
/* Update the sensor data, so that getters are nonblocking.
|
||||||
* Returns a bool of whether data was updated or not.
|
* Returns a bool of whether data was updated or not.
|
||||||
@ -162,10 +162,11 @@ public:
|
|||||||
virtual uint16_t error_count(void) const { return 0; }
|
virtual uint16_t error_count(void) const { return 0; }
|
||||||
virtual bool healthy(void) const { return get_gyro_health() && get_accel_health(); }
|
virtual bool healthy(void) const { return get_gyro_health() && get_accel_health(); }
|
||||||
|
|
||||||
|
virtual uint8_t get_primary_accel(void) const { return 0; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
virtual uint8_t _get_primary_gyro(void) const { return 0; }
|
virtual uint8_t _get_primary_gyro(void) const { return 0; }
|
||||||
virtual uint8_t _get_primary_accel(void) const { return 0; }
|
|
||||||
|
|
||||||
// sensor specific init to be overwritten by descendant classes
|
// sensor specific init to be overwritten by descendant classes
|
||||||
virtual uint16_t _init_sensor( Sample_rate sample_rate ) = 0;
|
virtual uint16_t _init_sensor( Sample_rate sample_rate ) = 0;
|
||||||
|
@ -252,7 +252,7 @@ uint8_t AP_InertialSensor_PX4::_get_primary_gyro(void) const
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t AP_InertialSensor_PX4::_get_primary_accel(void) const
|
uint8_t AP_InertialSensor_PX4::get_primary_accel(void) const
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<_num_accel_instances; i++) {
|
for (uint8_t i=0; i<_num_accel_instances; i++) {
|
||||||
if (get_accel_health(i)) return i;
|
if (get_accel_health(i)) return i;
|
||||||
|
@ -38,9 +38,10 @@ public:
|
|||||||
bool get_accel_health(uint8_t instance) const;
|
bool get_accel_health(uint8_t instance) const;
|
||||||
uint8_t get_accel_count(void) const;
|
uint8_t get_accel_count(void) const;
|
||||||
|
|
||||||
|
uint8_t get_primary_accel(void) const;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
uint8_t _get_primary_gyro(void) const;
|
uint8_t _get_primary_gyro(void) const;
|
||||||
uint8_t _get_primary_accel(void) const;
|
|
||||||
|
|
||||||
uint16_t _init_sensor( Sample_rate sample_rate );
|
uint16_t _init_sensor( Sample_rate sample_rate );
|
||||||
void _get_sample(void);
|
void _get_sample(void);
|
||||||
|
Loading…
Reference in New Issue
Block a user