MLECO-1868: Code static analyzer warnings fixes

Signed-off-by: alexander <alexander.efremov@arm.com>
Change-Id: Ie423e9cad3fabec6ab077ded7236813fe4933dea
diff --git a/source/application/hal/hal.c b/source/application/hal/hal.c
index dbf94ba..9c2ce32 100644
--- a/source/application/hal/hal.c
+++ b/source/application/hal/hal.c
@@ -32,7 +32,7 @@
  * @brief   Initialises the Arm Ethos-U55 NPU
  * @return  0 if successful, error code otherwise
  **/
-static int _arm_npu_init(void);
+static int arm_npu_init(void);
 
 #endif /* ARM_NPU */
 
@@ -54,7 +54,7 @@
 /**
  * @brief  Local helper function to clean the slate for current platform.
  **/
-static void _hal_platform_clear(hal_platform* platform)
+static void hal_platform_clear(hal_platform* platform)
 {
     assert(platform);
     platform->inited = 0;
@@ -64,7 +64,7 @@
 {
     int state;
     assert(platform && platform->platform_init);
-    _hal_platform_clear(platform);
+    hal_platform_clear(platform);
 
     /* Initialise platform */
     if (0 != (state = platform->platform_init())) {
@@ -94,7 +94,7 @@
 #if defined(ARM_NPU)
 
     /* If Arm Ethos-U55 NPU is to be used, we initialise it here */
-    if (0 != (state = _arm_npu_init())) {
+    if (0 != (state = arm_npu_init())) {
         return state;
     }
 
@@ -120,7 +120,7 @@
     data_acq_channel_release(platform->data_acq);
     data_psn_system_release(platform->data_psn);
 
-    _hal_platform_clear(platform);
+    hal_platform_clear(platform);
     info("releasing platform %s\n", platform->plat_name);
     platform->platform_release();
 }
@@ -130,7 +130,7 @@
  * @brief   Defines the Ethos-U interrupt handler: just a wrapper around the default
  *          implementation.
  **/
-static void _arm_npu_irq_handler(void)
+static void arm_npu_irq_handler(void)
 {
     /* Call the default interrupt handler from the NPU driver */
     ethosu_irq_handler();
@@ -139,19 +139,19 @@
 /**
  * @brief  Initialises the NPU IRQ
  **/
-static void _arm_npu_irq_init(void)
+static void arm_npu_irq_init(void)
 {
     const IRQn_Type ethosu_irqnum = (IRQn_Type)EthosU_IRQn;
 
     /* Register the EthosU IRQ handler in our vector table.
      * Note, this handler comes from the EthosU driver */
-    NVIC_SetVector(ethosu_irqnum, (uint32_t)_arm_npu_irq_handler);
+    NVIC_SetVector(ethosu_irqnum, (uint32_t)arm_npu_irq_handler);
 
     /* Enable the IRQ */
     NVIC_EnableIRQ(ethosu_irqnum);
 
     debug("EthosU IRQ#: %u, Handler: 0x%p\n",
-            ethosu_irqnum, _arm_npu_irq_handler);
+            ethosu_irqnum, arm_npu_irq_handler);
 }
 
 static int _arm_npu_timing_adapter_init(void)
@@ -213,7 +213,7 @@
     return 0;
 }
 
-static int _arm_npu_init(void)
+static int arm_npu_init(void)
 {
     int err = 0;
 
@@ -224,7 +224,7 @@
     }
 
     /* Initialise the IRQ */
-    _arm_npu_irq_init();
+    arm_npu_irq_init();
 
     /* Initialise Ethos-U55 device */
     const void * ethosu_base_address = (void *)(SEC_ETHOS_U55_BASE);
diff --git a/source/application/main/Classifier.cc b/source/application/main/Classifier.cc
index bc2c378..9a47f3d 100644
--- a/source/application/main/Classifier.cc
+++ b/source/application/main/Classifier.cc
@@ -28,10 +28,46 @@
 namespace app {
 
     template<typename T>
-    bool Classifier::_GetTopNResults(TfLiteTensor* tensor,
-                         std::vector<ClassificationResult>& vecResults,
-                         uint32_t topNCount,
-                         const std::vector <std::string>& labels)
+    void SetVectorResults(std::set<std::pair<T, uint32_t>>& topNSet,
+                          std::vector<ClassificationResult>& vecResults,
+                          TfLiteTensor* tensor,
+                          const std::vector <std::string>& labels) {
+
+        /* For getting the floating point values, we need quantization parameters. */
+        QuantParams quantParams = GetTensorQuantParams(tensor);
+
+        /* Reset the iterator to the largest element - use reverse iterator. */
+        auto topNIter = topNSet.rbegin();
+        for (size_t i = 0; i < vecResults.size() && topNIter != topNSet.rend(); ++i, ++topNIter) {
+            T score = topNIter->first;
+            vecResults[i].m_normalisedVal = quantParams.scale * (score - quantParams.offset);
+            vecResults[i].m_label = labels[topNIter->second];
+            vecResults[i].m_labelIdx = topNIter->second;
+        }
+
+    }
+
+    template<>
+    void SetVectorResults<float>(std::set<std::pair<float, uint32_t>>& topNSet,
+                          std::vector<ClassificationResult>& vecResults,
+                          TfLiteTensor* tensor,
+                          const std::vector <std::string>& labels) {
+        UNUSED(tensor);
+        /* Reset the iterator to the largest element - use reverse iterator. */
+        auto topNIter = topNSet.rbegin();
+        for (size_t i = 0; i < vecResults.size() && topNIter != topNSet.rend(); ++i, ++topNIter) {
+            vecResults[i].m_normalisedVal = topNIter->first;
+            vecResults[i].m_label = labels[topNIter->second];
+            vecResults[i].m_labelIdx = topNIter->second;
+        }
+
+    }
+
+    template<typename T>
+    bool Classifier::GetTopNResults(TfLiteTensor* tensor,
+                                    std::vector<ClassificationResult>& vecResults,
+                                    uint32_t topNCount,
+                                    const std::vector <std::string>& labels)
     {
         std::set<std::pair<T, uint32_t>> sortedSet;
 
@@ -59,82 +95,18 @@
         /* Final results' container. */
         vecResults = std::vector<ClassificationResult>(topNCount);
 
-        /* For getting the floating point values, we need quantization parameters. */
-        QuantParams quantParams = GetTensorQuantParams(tensor);
-
-        /* Reset the iterator to the largest element - use reverse iterator. */
-        auto setRevIter = sortedSet.rbegin();
-
-        /* Populate results
-         * Note: we could combine this loop with the loop above, but that
-         *       would, involve more multiplications and other operations.
-         **/
-        for (size_t i = 0; i < vecResults.size(); ++i, ++setRevIter) {
-            double score = static_cast<int> (setRevIter->first);
-            vecResults[i].m_normalisedVal = quantParams.scale *
-                                         (score - quantParams.offset);
-            vecResults[i].m_label = labels[setRevIter->second];
-            vecResults[i].m_labelIdx = setRevIter->second;
-        }
+        SetVectorResults<T>(sortedSet, vecResults, tensor, labels);
 
         return true;
     }
 
-    template<>
-    bool Classifier::_GetTopNResults<float>(TfLiteTensor* tensor,
-                                     std::vector<ClassificationResult>& vecResults,
-                                     uint32_t topNCount,
-                                     const std::vector <std::string>& labels)
-    {
-        std::set<std::pair<float, uint32_t>> sortedSet;
+    template bool  Classifier::GetTopNResults<uint8_t>(TfLiteTensor* tensor,
+                                                       std::vector<ClassificationResult>& vecResults,
+                                                       uint32_t topNCount, const std::vector <std::string>& labels);
 
-        /* NOTE: inputVec's size verification against labels should be
-         *       checked by the calling/public function. */
-        float* tensorData = tflite::GetTensorData<float>(tensor);
-
-        /* Set initial elements. */
-        for (uint32_t i = 0; i < topNCount; ++i) {
-            sortedSet.insert({tensorData[i], i});
-        }
-
-        /* Initialise iterator. */
-        auto setFwdIter = sortedSet.begin();
-
-        /* Scan through the rest of elements with compare operations. */
-        for (uint32_t i = topNCount; i < labels.size(); ++i) {
-            if (setFwdIter->first < tensorData[i]) {
-                sortedSet.erase(*setFwdIter);
-                sortedSet.insert({tensorData[i], i});
-                setFwdIter = sortedSet.begin();
-            }
-        }
-
-        /* Final results' container. */
-        vecResults = std::vector<ClassificationResult>(topNCount);
-
-        /* Reset the iterator to the largest element - use reverse iterator. */
-        auto setRevIter = sortedSet.rbegin();
-
-        /* Populate results
-         * Note: we could combine this loop with the loop above, but that
-         *       would, involve more multiplications and other operations.
-         **/
-        for (size_t i = 0; i < vecResults.size(); ++i, ++setRevIter) {
-            vecResults[i].m_normalisedVal = setRevIter->first;
-            vecResults[i].m_label = labels[setRevIter->second];
-            vecResults[i].m_labelIdx = setRevIter->second;
-        }
-
-        return true;
-    }
-
-    template bool  Classifier::_GetTopNResults<uint8_t>(TfLiteTensor* tensor,
-                                           std::vector<ClassificationResult>& vecResults,
-                                           uint32_t topNCount, const std::vector <std::string>& labels);
-
-    template bool  Classifier::_GetTopNResults<int8_t>(TfLiteTensor* tensor,
-                                          std::vector<ClassificationResult>& vecResults,
-                                          uint32_t topNCount, const std::vector <std::string>& labels);
+    template bool  Classifier::GetTopNResults<int8_t>(TfLiteTensor* tensor,
+                                                      std::vector<ClassificationResult>& vecResults,
+                                                      uint32_t topNCount, const std::vector <std::string>& labels);
 
     bool  Classifier::GetClassificationResults(
         TfLiteTensor* outputTensor,
@@ -158,6 +130,9 @@
         } else if (totalOutputSize != labels.size()) {
             printf_err("Output size doesn't match the labels' size\n");
             return false;
+        } else if (topNCount == 0) {
+            printf_err("Top N results cannot be zero\n");
+            return false;
         }
 
         bool resultState;
@@ -166,13 +141,13 @@
         /* Get the top N results. */
         switch (outputTensor->type) {
             case kTfLiteUInt8:
-                resultState = _GetTopNResults<uint8_t>(outputTensor, vecResults, topNCount, labels);
+                resultState = GetTopNResults<uint8_t>(outputTensor, vecResults, topNCount, labels);
                 break;
             case kTfLiteInt8:
-                resultState = _GetTopNResults<int8_t>(outputTensor, vecResults, topNCount, labels);
+                resultState = GetTopNResults<int8_t>(outputTensor, vecResults, topNCount, labels);
                 break;
             case kTfLiteFloat32:
-                resultState = _GetTopNResults<float>(outputTensor, vecResults, topNCount, labels);
+                resultState = GetTopNResults<float>(outputTensor, vecResults, topNCount, labels);
                 break;
             default:
                 printf_err("Tensor type %s not supported by classifier\n", TfLiteTypeGetName(outputTensor->type));
@@ -180,7 +155,7 @@
         }
 
         if (!resultState) {
-            printf_err("Failed to get sorted set\n");
+            printf_err("Failed to get top N results set\n");
             return false;
         }
 
diff --git a/source/application/main/Mfcc.cc b/source/application/main/Mfcc.cc
index bf16159..9ddcb5d 100644
--- a/source/application/main/Mfcc.cc
+++ b/source/application/main/Mfcc.cc
@@ -44,7 +44,7 @@
                         m_useHtkMethod(useHtkMethod)
     {}
 
-    std::string MfccParams::Str()
+    std::string MfccParams::Str() const
     {
         char strC[1024];
         snprintf(strC, sizeof(strC) - 1, "\n   \
@@ -74,7 +74,7 @@
                                 this->_m_params.m_numFbankBins, 0.0);
 
         this->_m_windowFunc = std::vector<float>(this->_m_params.m_frameLen);
-        const float multiplier = 2 * M_PI / this->_m_params.m_frameLen;
+        const auto multiplier = static_cast<float>(2 * M_PI / this->_m_params.m_frameLen);
 
         /* Create window function. */
         for (size_t i = 0; i < this->_m_params.m_frameLen; i++) {
@@ -88,7 +88,7 @@
 
     void MFCC::Init()
     {
-        this->_InitMelFilterBank();
+        this->InitMelFilterBank();
     }
 
     float MFCC::MelScale(const float freq, const bool useHTKMethod)
@@ -126,8 +126,8 @@
     bool MFCC::ApplyMelFilterBank(
             std::vector<float>&                 fftVec,
             std::vector<std::vector<float>>&    melFilterBank,
-            std::vector<int32_t>&               filterBankFilterFirst,
-            std::vector<int32_t>&               filterBankFilterLast,
+            std::vector<uint32_t>&               filterBankFilterFirst,
+            std::vector<uint32_t>&               filterBankFilterLast,
             std::vector<float>&                 melEnergies)
     {
         const size_t numBanks = melEnergies.size();
@@ -140,11 +140,12 @@
 
         for (size_t bin = 0; bin < numBanks; ++bin) {
             auto filterBankIter = melFilterBank[bin].begin();
+            auto end = melFilterBank[bin].end();
             float melEnergy = FLT_MIN;  /* Avoid log of zero at later stages */
-            int32_t firstIndex = filterBankFilterFirst[bin];
-            int32_t lastIndex = filterBankFilterLast[bin];
+            const uint32_t firstIndex = filterBankFilterFirst[bin];
+            const uint32_t lastIndex = std::min<uint32_t>(filterBankFilterLast[bin], fftVec.size() - 1);
 
-            for (int i = firstIndex; i <= lastIndex; i++) {
+            for (uint32_t i = firstIndex; i <= lastIndex && filterBankIter != end; i++) {
                 float energyRep = math::MathUtils::SqrtF32(fftVec[i]);
                 melEnergy += (*filterBankIter++ * energyRep);
             }
@@ -157,14 +158,14 @@
 
     void MFCC::ConvertToLogarithmicScale(std::vector<float>& melEnergies)
     {
-        for (size_t bin = 0; bin < melEnergies.size(); ++bin) {
-            melEnergies[bin] = logf(melEnergies[bin]);
+        for (float& melEnergy : melEnergies) {
+            melEnergy = logf(melEnergy);
         }
     }
 
-    void MFCC::_ConvertToPowerSpectrum()
+    void MFCC::ConvertToPowerSpectrum()
     {
-        const uint32_t halfDim = this->_m_params.m_frameLenPadded / 2;
+        const uint32_t halfDim = this->_m_buffer.size() / 2;
 
         /* Handle this special case. */
         float firstEnergy = this->_m_buffer[0] * this->_m_buffer[0];
@@ -193,7 +194,7 @@
         for (int32_t k = 0, m = 0; k < coefficientCount; k++, m += inputLength) {
             for (int32_t n = 0; n < inputLength; n++) {
                 dctMatix[m+n] = normalizer *
-                    math::MathUtils::CosineF32((n + 0.5) * angle);
+                    math::MathUtils::CosineF32((n + 0.5f) * angle);
             }
             angle += angleIncr;
         }
@@ -214,10 +215,10 @@
         return 1.f;
     }
 
-    void MFCC::_InitMelFilterBank()
+    void MFCC::InitMelFilterBank()
     {
-        if (!this->_IsMelFilterBankInited()) {
-            this->_m_melFilterBank = this->_CreateMelFilterBank();
+        if (!this->IsMelFilterBankInited()) {
+            this->_m_melFilterBank = this->CreateMelFilterBank();
             this->_m_dctMatrix = this->CreateDCTMatrix(
                                     this->_m_params.m_numFbankBins,
                                     this->_m_params.m_numMfccFeatures);
@@ -225,17 +226,17 @@
         }
     }
 
-    bool MFCC::_IsMelFilterBankInited()
+    bool MFCC::IsMelFilterBankInited() const
     {
         return this->_m_filterBankInitialised;
     }
 
-    void MFCC::_MfccComputePreFeature(const std::vector<int16_t>& audioData)
+    void MFCC::MfccComputePreFeature(const std::vector<int16_t>& audioData)
     {
-        this->_InitMelFilterBank();
+        this->InitMelFilterBank();
 
         /* TensorFlow way of normalizing .wav data to (-1, 1). */
-        constexpr float normaliser = 1.0/(1<<15);
+        constexpr float normaliser = 1.0/(1u<<15u);
         for (size_t i = 0; i < this->_m_params.m_frameLen; i++) {
             this->_m_frame[i] = static_cast<float>(audioData[i]) * normaliser;
         }
@@ -252,7 +253,7 @@
         math::MathUtils::FftF32(this->_m_frame, this->_m_buffer, this->_m_fftInstance);
 
         /* Convert to power spectrum. */
-        this->_ConvertToPowerSpectrum();
+        this->ConvertToPowerSpectrum();
 
         /* Apply mel filterbanks. */
         if (!this->ApplyMelFilterBank(this->_m_buffer,
@@ -269,7 +270,7 @@
 
     std::vector<float> MFCC::MfccCompute(const std::vector<int16_t>& audioData)
     {
-        this->_MfccComputePreFeature(audioData);
+        this->MfccComputePreFeature(audioData);
 
         std::vector<float> mfccOut(this->_m_params.m_numMfccFeatures);
 
@@ -288,7 +289,7 @@
         return mfccOut;
     }
 
-    std::vector<std::vector<float>> MFCC::_CreateMelFilterBank()
+    std::vector<std::vector<float>> MFCC::CreateMelFilterBank()
     {
         size_t numFftBins = this->_m_params.m_frameLenPadded / 2;
         float fftBinWidth = static_cast<float>(this->_m_params.m_samplingFreq) / this->_m_params.m_frameLenPadded;
@@ -303,17 +304,18 @@
         std::vector<std::vector<float>> melFilterBank(
                                             this->_m_params.m_numFbankBins);
         this->_m_filterBankFilterFirst =
-                        std::vector<int32_t>(this->_m_params.m_numFbankBins);
+                        std::vector<uint32_t>(this->_m_params.m_numFbankBins);
         this->_m_filterBankFilterLast =
-                        std::vector<int32_t>(this->_m_params.m_numFbankBins);
+                        std::vector<uint32_t>(this->_m_params.m_numFbankBins);
 
         for (size_t bin = 0; bin < this->_m_params.m_numFbankBins; bin++) {
             float leftMel = melLowFreq + bin * melFreqDelta;
             float centerMel = melLowFreq + (bin + 1) * melFreqDelta;
             float rightMel = melLowFreq + (bin + 2) * melFreqDelta;
 
-            int32_t firstIndex = -1;
-            int32_t lastIndex = -1;
+            uint32_t firstIndex = 0;
+            uint32_t lastIndex = 0;
+            bool firstIndexFound = false;
             const float normaliser = this->GetMelFilterBankNormaliser(leftMel, rightMel, this->_m_params.m_useHtkMethod);
 
             for (size_t i = 0; i < numFftBins; i++) {
@@ -330,8 +332,9 @@
                     }
 
                     thisBin[i] = weight * normaliser;
-                    if (firstIndex == -1) {
+                    if (!firstIndexFound) {
                         firstIndex = i;
+                        firstIndexFound = true;
                     }
                     lastIndex = i;
                 }
@@ -341,7 +344,7 @@
             this->_m_filterBankFilterLast[bin] = lastIndex;
 
             /* Copy the part we care about. */
-            for (int32_t i = firstIndex; i <= lastIndex; i++) {
+            for (uint32_t i = firstIndex; i <= lastIndex; i++) {
                 melFilterBank[bin].push_back(thisBin[i]);
             }
         }
diff --git a/source/application/main/PlatformMath.cc b/source/application/main/PlatformMath.cc
index a9f5049..9d18151 100644
--- a/source/application/main/PlatformMath.cc
+++ b/source/application/main/PlatformMath.cc
@@ -121,7 +121,7 @@
             float sumReal = 0, sumImag = 0;
 
             for (int t = 0; t < inputLength; t++) {
-                float angle = 2 * M_PI * t * k / inputLength;
+                auto angle = static_cast<float>(2 * M_PI * t * k / inputLength);
                 sumReal += input[t] * cosf(angle);
                 sumImag += -input[t] * sinf(angle);
             }
@@ -147,7 +147,7 @@
                      output.size());
 #else /* ARM_DSP_AVAILABLE */
         for (auto in = input.begin(), out = output.begin();
-                in != input.end(); ++in, ++out) {
+             in != input.end() && out != output.end(); ++in, ++out) {
             *out = logf(*in);
         }
 #endif /* ARM_DSP_AVAILABLE */
diff --git a/source/application/main/Profiler.cc b/source/application/main/Profiler.cc
index 0456ba4..10a828a 100644
--- a/source/application/main/Profiler.cc
+++ b/source/application/main/Profiler.cc
@@ -54,7 +54,7 @@
             this->_m_tstampEnd = this->_m_pPlatform->timer->stop_profiling();
             this->_m_started = false;
 
-            this->_AddProfilingUnit(this->_m_tstampSt, this->_m_tstampEnd, this->_m_name);
+            this->AddProfilingUnit(this->_m_tstampSt, this->_m_tstampEnd, this->_m_name);
 
             return true;
         }
@@ -238,8 +238,8 @@
         this->_m_name = std::string(str);
     }
 
-    void Profiler::_AddProfilingUnit(time_counter start, time_counter end,
-                                     const std::string& name)
+    void Profiler::AddProfilingUnit(time_counter start, time_counter end,
+                                    const std::string& name)
     {
         platform_timer * timer = this->_m_pPlatform->timer;
 
diff --git a/source/application/main/include/Classifier.hpp b/source/application/main/include/Classifier.hpp
index 510e6f9..3ee3148 100644
--- a/source/application/main/include/Classifier.hpp
+++ b/source/application/main/include/Classifier.hpp
@@ -62,7 +62,7 @@
          * @return      true if successful, false otherwise.
          **/
         template<typename T>
-        bool _GetTopNResults(TfLiteTensor* tensor,
+        bool GetTopNResults(TfLiteTensor* tensor,
                             std::vector<ClassificationResult>& vecResults,
                             uint32_t topNCount,
                             const std::vector <std::string>& labels);
diff --git a/source/application/main/include/DataStructures.hpp b/source/application/main/include/DataStructures.hpp
index 5cc8b5e..2f267c0 100644
--- a/source/application/main/include/DataStructures.hpp
+++ b/source/application/main/include/DataStructures.hpp
@@ -47,15 +47,13 @@
          * @param[in] rows   Number of rows.
          * @param[in] cols   Number of columns.
          */
-        Array2d(unsigned rows, unsigned cols)
+        Array2d(unsigned rows, unsigned cols): _m_rows(rows), _m_cols(cols)
         {
             if (rows == 0 || cols == 0) {
                 printf_err("Array2d constructor has 0 size.\n");
                 _m_data = nullptr;
                 return;
             }
-            _m_rows = rows;
-            _m_cols = cols;
             _m_data = new T[rows * cols];
         }
 
diff --git a/source/application/main/include/Mfcc.hpp b/source/application/main/include/Mfcc.hpp
index 6379fab..dcafe62 100644
--- a/source/application/main/include/Mfcc.hpp
+++ b/source/application/main/include/Mfcc.hpp
@@ -52,7 +52,7 @@
         ~MfccParams() = default;
 
         /** @brief  String representation of parameters */
-        std::string Str();
+        std::string Str() const;
     };
 
     /**
@@ -100,7 +100,7 @@
                                         const float quantScale,
                                         const int quantOffset)
         {
-            this->_MfccComputePreFeature(audioData);
+            this->MfccComputePreFeature(audioData);
             float minVal = std::numeric_limits<T>::min();
             float maxVal = std::numeric_limits<T>::max();
 
@@ -154,7 +154,7 @@
          *              bank weights and adding them up to be placed into
          *              bins, according to the filter bank's first and last
          *              indices (pre-computed for each filter bank element
-         *              by _CreateMelFilterBank function).
+         *              by CreateMelFilterBank function).
          * @param[in]   fftVec                  Vector populated with FFT magnitudes.
          * @param[in]   melFilterBank           2D Vector with filter bank weights.
          * @param[in]   filterBankFilterFirst   Vector containing the first indices of filter bank
@@ -168,8 +168,8 @@
         virtual bool ApplyMelFilterBank(
             std::vector<float>&                 fftVec,
             std::vector<std::vector<float>>&    melFilterBank,
-            std::vector<int32_t>&               filterBankFilterFirst,
-            std::vector<int32_t>&               filterBankFilterLast,
+            std::vector<uint32_t>&               filterBankFilterFirst,
+            std::vector<uint32_t>&               filterBankFilterLast,
             std::vector<float>&                 melEnergies);
 
         /**
@@ -214,37 +214,37 @@
         std::vector<float>              _m_windowFunc;
         std::vector<std::vector<float>> _m_melFilterBank;
         std::vector<float>              _m_dctMatrix;
-        std::vector<int32_t>            _m_filterBankFilterFirst;
-        std::vector<int32_t>            _m_filterBankFilterLast;
+        std::vector<uint32_t>           _m_filterBankFilterFirst;
+        std::vector<uint32_t>           _m_filterBankFilterLast;
         bool                            _m_filterBankInitialised;
         arm::app::math::FftInstance     _m_fftInstance;
 
         /**
          * @brief       Initialises the filter banks and the DCT matrix. **/
-        void _InitMelFilterBank();
+        void InitMelFilterBank();
 
         /**
          * @brief       Signals whether the instance of MFCC has had its
          *              required buffers initialised.
          * @return      true if initialised, false otherwise.
          **/
-        bool _IsMelFilterBankInited();
+        bool IsMelFilterBankInited() const;
 
         /**
          * @brief       Create mel filter banks for MFCC calculation.
          * @return      2D vector of floats.
          **/
-        std::vector<std::vector<float>> _CreateMelFilterBank();
+        std::vector<std::vector<float>> CreateMelFilterBank();
 
         /**
          * @brief       Computes and populates internal memeber buffers used
          *              in MFCC feature calculation
          * @param[in]   audioData   1D vector of 16-bit audio data.
          */
-        void _MfccComputePreFeature(const std::vector<int16_t>& audioData);
+        void MfccComputePreFeature(const std::vector<int16_t>& audioData);
 
         /** @brief       Computes the magnitude from an interleaved complex array. */
-        void _ConvertToPowerSpectrum();
+        void ConvertToPowerSpectrum();
 
     };
 
diff --git a/source/application/main/include/Profiler.hpp b/source/application/main/include/Profiler.hpp
index d93b257..c5f77e7 100644
--- a/source/application/main/include/Profiler.hpp
+++ b/source/application/main/include/Profiler.hpp
@@ -125,8 +125,8 @@
          * @param[in]   name    Name for the profiling unit series to be
          *                      appended to.
          **/
-        void _AddProfilingUnit(time_counter start, time_counter end,
-                               const std::string& name);
+        void AddProfilingUnit(time_counter start, time_counter end,
+                              const std::string& name);
     };
 
 } /* namespace app */
diff --git a/source/application/tensorflow-lite-micro/Model.cc b/source/application/tensorflow-lite-micro/Model.cc
index 0775467..abf97b6 100644
--- a/source/application/tensorflow-lite-micro/Model.cc
+++ b/source/application/tensorflow-lite-micro/Model.cc
@@ -317,7 +317,7 @@
 }
 namespace arm {
 namespace app {
-    static uint8_t  _tensor_arena[ACTIVATION_BUF_SZ] ACTIVATION_BUF_ATTRIBUTE;
+    static uint8_t  tensor_arena[ACTIVATION_BUF_SZ] ACTIVATION_BUF_ATTRIBUTE;
 } /* namespace app */
 } /* namespace arm */
 
@@ -328,5 +328,5 @@
 
 uint8_t *arm::app::Model::GetTensorArena()
 {
-    return _tensor_arena;
+    return tensor_arena;
 }
\ No newline at end of file