mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_HAL_SITL: add vector addition function
This commit is contained in:
parent
884454cd88
commit
3199412bff
@ -137,6 +137,13 @@ void DSP::vector_scale_float(const float* vin, float scale, float* vout, uint16_
|
||||
}
|
||||
}
|
||||
|
||||
void DSP::vector_add_float(const float* vin1, const float* vin2, float* vout, uint16_t len) const
|
||||
{
|
||||
for (uint16_t i = 0; i < len; i++) {
|
||||
vout[i] = vin1[i] + vin2[i];
|
||||
}
|
||||
}
|
||||
|
||||
float DSP::vector_mean_float(const float* vin, uint16_t len) const
|
||||
{
|
||||
float mean_value = 0.0f;
|
||||
|
@ -52,5 +52,6 @@ private:
|
||||
void vector_max_float(const float* vin, uint16_t len, float* maxValue, uint16_t* maxIndex) const override;
|
||||
void vector_scale_float(const float* vin, float scale, float* vout, uint16_t len) const override;
|
||||
float vector_mean_float(const float* vin, uint16_t len) const override;
|
||||
void vector_add_float(const float* vin1, const float* vin2, float* vout, uint16_t len) const override;
|
||||
void calculate_fft(complexf* f, uint16_t length);
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user