mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_HAL_ChibiOS: add vector addition function
This commit is contained in:
parent
f57ac4787d
commit
884454cd88
@ -61,6 +61,9 @@ protected:
|
|||||||
arm_mean_f32(vin, len, &mean_value);
|
arm_mean_f32(vin, len, &mean_value);
|
||||||
return mean_value;
|
return mean_value;
|
||||||
}
|
}
|
||||||
|
void vector_add_float(const float* vin1, const float* vin2, float* vout, uint16_t len) const override {
|
||||||
|
arm_add_f32(vin1, vin2, vout, len);
|
||||||
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
// following are the six independent steps for calculating an FFT
|
// following are the six independent steps for calculating an FFT
|
||||||
|
Loading…
Reference in New Issue
Block a user