diff --git a/libraries/AP_HAL_SITL/DSP.cpp b/libraries/AP_HAL_SITL/DSP.cpp index b8ca324342..b176c0c14b 100644 --- a/libraries/AP_HAL_SITL/DSP.cpp +++ b/libraries/AP_HAL_SITL/DSP.cpp @@ -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; diff --git a/libraries/AP_HAL_SITL/DSP.h b/libraries/AP_HAL_SITL/DSP.h index 04bb410a61..6d7421e31f 100644 --- a/libraries/AP_HAL_SITL/DSP.h +++ b/libraries/AP_HAL_SITL/DSP.h @@ -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); };