COMPMID-2177 Fix clang warnings

Change-Id: I4beacfd714ee3ed771fd174cce5d8009a2961380
Signed-off-by: Michalis Spyrou <michalis.spyrou@arm.com>
Reviewed-on: https://review.mlplatform.org/c/1065
Reviewed-by: Giuseppe Rossini <giuseppe.rossini@arm.com>
Tested-by: Arm Jenkins <bsgcomp@arm.com>
diff --git a/arm_compute/core/utils/logging/LoggerRegistry.h b/arm_compute/core/utils/logging/LoggerRegistry.h
index 066a42f..c841020 100644
--- a/arm_compute/core/utils/logging/LoggerRegistry.h
+++ b/arm_compute/core/utils/logging/LoggerRegistry.h
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2017-2018 ARM Limited.
+ * Copyright (c) 2017-2019 ARM Limited.
  *
  * SPDX-License-Identifier: MIT
  *
@@ -73,8 +73,8 @@
      * @param[in] log_level (Optional) Logger's log level. Defaults to INFO
      * @param[in] printers  (Optional) Printers to attach to the system loggers. Defaults with a @ref StdPrinter.
      */
-    void create_reserved_loggers(LogLevel                              log_level = LogLevel::INFO,
-                                 std::vector<std::shared_ptr<Printer>> printers  = { std::make_shared<StdPrinter>() });
+    void create_reserved_loggers(LogLevel                                     log_level = LogLevel::INFO,
+                                 const std::vector<std::shared_ptr<Printer>> &printers  = { std::make_shared<StdPrinter>() });
 
 private:
     /** Default constructor */
diff --git a/arm_compute/graph/Graph.h b/arm_compute/graph/Graph.h
index 2a77682..878976f 100644
--- a/arm_compute/graph/Graph.h
+++ b/arm_compute/graph/Graph.h
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2018 ARM Limited.
+ * Copyright (c) 2018-2019 ARM Limited.
  *
  * SPDX-License-Identifier: MIT
  *
@@ -216,7 +216,7 @@
      *
      * @return Tensor ID
      */
-    TensorID create_tensor(TensorDescriptor desc = TensorDescriptor());
+    TensorID create_tensor(const TensorDescriptor &desc = TensorDescriptor());
 
 private:
     GraphID                              _id      = GraphID(0); /**< Graph id */
diff --git a/arm_compute/graph/GraphBuilder.h b/arm_compute/graph/GraphBuilder.h
index f1d387b..1d6ecc8 100644
--- a/arm_compute/graph/GraphBuilder.h
+++ b/arm_compute/graph/GraphBuilder.h
@@ -51,7 +51,7 @@
      *
      * @return Node ID of the created node, EmptyNodeID in case of error
      */
-    static NodeID add_const_node(Graph &g, NodeParams params, TensorDescriptor desc, ITensorAccessorUPtr accessor = nullptr);
+    static NodeID add_const_node(Graph &g, NodeParams params, const TensorDescriptor &desc, ITensorAccessorUPtr accessor = nullptr);
     /** Adds an input layer node to the graph
      *
      * @param[in] g        Graph to add the node to
@@ -61,7 +61,7 @@
      *
      * @return Node ID of the created node, EmptyNodeID in case of error
      */
-    static NodeID add_input_node(Graph &g, NodeParams params, TensorDescriptor desc, ITensorAccessorUPtr accessor = nullptr);
+    static NodeID add_input_node(Graph &g, NodeParams params, const TensorDescriptor &desc, ITensorAccessorUPtr accessor = nullptr);
     /** Adds an output layer node to the graph
      *
      * @param[in] g        Graph to add the node to
diff --git a/arm_compute/graph/Tensor.h b/arm_compute/graph/Tensor.h
index 54fb258..07eec1e 100644
--- a/arm_compute/graph/Tensor.h
+++ b/arm_compute/graph/Tensor.h
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2018 ARM Limited.
+ * Copyright (c) 2018-2019 ARM Limited.
  *
  * SPDX-License-Identifier: MIT
  *
@@ -108,7 +108,7 @@
      *
      * @return Bound edges
      */
-    const std::set<EdgeID> bound_edges() const;
+    std::set<EdgeID> bound_edges() const;
 
 private:
     TensorID                         _id;          /**< Tensor id */
diff --git a/arm_compute/runtime/GLES_COMPUTE/functions/GCDepthConcatenateLayer.h b/arm_compute/runtime/GLES_COMPUTE/functions/GCDepthConcatenateLayer.h
index 307ec49..da00f38 100644
--- a/arm_compute/runtime/GLES_COMPUTE/functions/GCDepthConcatenateLayer.h
+++ b/arm_compute/runtime/GLES_COMPUTE/functions/GCDepthConcatenateLayer.h
@@ -60,9 +60,9 @@
     void run() override;
 
 private:
-    std::unique_ptr<GCDepthConcatenateLayerKernel[]> _concat_kernels_vector;
-    std::unique_ptr<GCFillBorderKernel[]>            _border_handlers_vector;
-    unsigned int                                     _num_inputs;
+    std::vector<std::unique_ptr<GCDepthConcatenateLayerKernel>> _concat_kernels_vector;
+    std::vector<std::unique_ptr<GCFillBorderKernel>>            _border_handlers_vector;
+    unsigned int                                                _num_inputs;
 };
 }
 #endif /* __ARM_COMPUTE_GCDEPTHCONCATENATE_H__ */
diff --git a/arm_compute/runtime/NEON/functions/NECropResize.h b/arm_compute/runtime/NEON/functions/NECropResize.h
index e790e68..53e8f7f 100644
--- a/arm_compute/runtime/NEON/functions/NECropResize.h
+++ b/arm_compute/runtime/NEON/functions/NECropResize.h
@@ -98,10 +98,10 @@
     InterpolationPolicy _method;
     float               _extrapolation_value;
 
-    std::unique_ptr<NECropKernel[]> _crop;
-    std::unique_ptr<NEScale[]>      _scale;
-    std::unique_ptr<Tensor[]>       _crop_results{ nullptr };
-    std::unique_ptr<Tensor[]>       _scaled_results{ nullptr };
+    std::vector<std::unique_ptr<NECropKernel>> _crop;
+    std::vector<std::unique_ptr<NEScale>>      _scale;
+    std::vector<std::unique_ptr<Tensor>>       _crop_results;
+    std::vector<std::unique_ptr<Tensor>>       _scaled_results;
 };
 } // namespace arm_compute
 #endif /* __ARM_COMPUTE_NEON_CROP_RESIZE_H__ */
diff --git a/arm_compute/runtime/NEON/functions/NEDepthConcatenateLayer.h b/arm_compute/runtime/NEON/functions/NEDepthConcatenateLayer.h
index e2f2c4c..b3bf752 100644
--- a/arm_compute/runtime/NEON/functions/NEDepthConcatenateLayer.h
+++ b/arm_compute/runtime/NEON/functions/NEDepthConcatenateLayer.h
@@ -84,10 +84,10 @@
     void run() override;
 
 private:
-    std::vector<ITensor *>                           _inputs_vector;
-    std::unique_ptr<NEDepthConcatenateLayerKernel[]> _concat_kernels_vector;
-    std::unique_ptr<NEFillBorderKernel[]>            _border_handlers_vector;
-    unsigned int                                     _num_inputs;
+    std::vector<ITensor *>                                      _inputs_vector;
+    std::vector<std::unique_ptr<NEDepthConcatenateLayerKernel>> _concat_kernels_vector;
+    std::vector<std::unique_ptr<NEFillBorderKernel>>            _border_handlers_vector;
+    unsigned int                                                _num_inputs;
 };
 } // namespace arm_compute
 #endif /* __ARM_COMPUTE_NEDEPTHCONCATENATE_H__ */
diff --git a/arm_compute/runtime/NEON/functions/NEGaussianPyramid.h b/arm_compute/runtime/NEON/functions/NEGaussianPyramid.h
index dbe0ecd..47fcd5e 100644
--- a/arm_compute/runtime/NEON/functions/NEGaussianPyramid.h
+++ b/arm_compute/runtime/NEON/functions/NEGaussianPyramid.h
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2016, 2017 ARM Limited.
+ * Copyright (c) 2016-2019 ARM Limited.
  *
  * SPDX-License-Identifier: MIT
  *
@@ -91,10 +91,10 @@
     void run() override;
 
 private:
-    std::unique_ptr<NEFillBorderKernel[]>          _horizontal_border_handler;
-    std::unique_ptr<NEFillBorderKernel[]>          _vertical_border_handler;
-    std::unique_ptr<NEGaussianPyramidHorKernel[]>  _horizontal_reduction;
-    std::unique_ptr<NEGaussianPyramidVertKernel[]> _vertical_reduction;
+    std::vector<std::unique_ptr<NEFillBorderKernel>>          _horizontal_border_handler;
+    std::vector<std::unique_ptr<NEFillBorderKernel>>          _vertical_border_handler;
+    std::vector<std::unique_ptr<NEGaussianPyramidHorKernel>>  _horizontal_reduction;
+    std::vector<std::unique_ptr<NEGaussianPyramidVertKernel>> _vertical_reduction;
 };
 
 /** Basic function to execute gaussian pyramid with ORB scale factor. This function calls the following NEON kernels and functions:
@@ -115,8 +115,8 @@
     void run() override;
 
 private:
-    std::unique_ptr<NEGaussian5x5[]> _gaus5x5;
-    std::unique_ptr<NEScale[]>       _scale_nearest;
+    std::vector<std::unique_ptr<NEGaussian5x5>> _gaus5x5;
+    std::vector<std::unique_ptr<NEScale>>       _scale_nearest;
 };
 }
 #endif /*__ARM_COMPUTE_NEGAUSSIANPYRAMID_H__ */
diff --git a/arm_compute/runtime/NEON/functions/NEHOGMultiDetection.h b/arm_compute/runtime/NEON/functions/NEHOGMultiDetection.h
index 0d268ca..e21f463 100644
--- a/arm_compute/runtime/NEON/functions/NEHOGMultiDetection.h
+++ b/arm_compute/runtime/NEON/functions/NEHOGMultiDetection.h
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2016, 2017 ARM Limited.
+ * Copyright (c) 2016-2019 ARM Limited.
  *
  * SPDX-License-Identifier: MIT
  *
@@ -91,12 +91,12 @@
 private:
     MemoryGroup                                                   _memory_group;
     NEHOGGradient                                                 _gradient_kernel;
-    std::unique_ptr<NEHOGOrientationBinningKernel[]>              _orient_bin_kernel;
-    std::unique_ptr<NEHOGBlockNormalizationKernel[]>              _block_norm_kernel;
-    std::unique_ptr<NEHOGDetector[]>                              _hog_detect_kernel;
+    std::vector<std::unique_ptr<NEHOGOrientationBinningKernel>>   _orient_bin_kernel;
+    std::vector<std::unique_ptr<NEHOGBlockNormalizationKernel>>   _block_norm_kernel;
+    std::vector<std::unique_ptr<NEHOGDetector>>                   _hog_detect_kernel;
     std::unique_ptr<CPPDetectionWindowNonMaximaSuppressionKernel> _non_maxima_kernel;
-    std::unique_ptr<Tensor[]>                                     _hog_space;
-    std::unique_ptr<Tensor[]>                                     _hog_norm_space;
+    std::vector<std::unique_ptr<Tensor>>                          _hog_space;
+    std::vector<std::unique_ptr<Tensor>>                          _hog_norm_space;
     IDetectionWindowArray                                        *_detection_windows;
     Tensor                                                        _mag;
     Tensor                                                        _phase;
diff --git a/arm_compute/runtime/NEON/functions/NEOpticalFlow.h b/arm_compute/runtime/NEON/functions/NEOpticalFlow.h
index ad703f0..320247d 100644
--- a/arm_compute/runtime/NEON/functions/NEOpticalFlow.h
+++ b/arm_compute/runtime/NEON/functions/NEOpticalFlow.h
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2016-2018 ARM Limited.
+ * Copyright (c) 2016-2019 ARM Limited.
  *
  * SPDX-License-Identifier: MIT
  *
@@ -86,17 +86,17 @@
     void run() override;
 
 private:
-    MemoryGroup                          _memory_group;
-    std::unique_ptr<NEScharr3x3[]>       _func_scharr;
-    std::unique_ptr<NELKTrackerKernel[]> _kernel_tracker;
-    std::unique_ptr<Tensor[]>            _scharr_gx;
-    std::unique_ptr<Tensor[]>            _scharr_gy;
-    IKeyPointArray                      *_new_points;
-    const IKeyPointArray                *_new_points_estimates;
-    const IKeyPointArray                *_old_points;
-    LKInternalKeypointArray              _new_points_internal;
-    LKInternalKeypointArray              _old_points_internal;
-    unsigned int                         _num_levels;
+    MemoryGroup                                     _memory_group;
+    std::vector<std::unique_ptr<NEScharr3x3>>       _func_scharr;
+    std::vector<std::unique_ptr<NELKTrackerKernel>> _kernel_tracker;
+    std::vector<std::unique_ptr<Tensor>>            _scharr_gx;
+    std::vector<std::unique_ptr<Tensor>>            _scharr_gy;
+    IKeyPointArray                                 *_new_points;
+    const IKeyPointArray                           *_new_points_estimates;
+    const IKeyPointArray                           *_old_points;
+    LKInternalKeypointArray                         _new_points_internal;
+    LKInternalKeypointArray                         _old_points_internal;
+    unsigned int                                    _num_levels;
 };
 }
 #endif /*__ARM_COMPUTE_NEOPTICALFLOW_H__ */
diff --git a/src/core/CL/kernels/CLConvolutionKernel.cpp b/src/core/CL/kernels/CLConvolutionKernel.cpp
index e677793..d9c7ede 100644
--- a/src/core/CL/kernels/CLConvolutionKernel.cpp
+++ b/src/core/CL/kernels/CLConvolutionKernel.cpp
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2016-2018 ARM Limited.
+ * Copyright (c) 2016-2019 ARM Limited.
  *
  * SPDX-License-Identifier: MIT
  *
@@ -39,9 +39,12 @@
 #include <sstream>
 #include <string>
 
-using namespace arm_compute;
-
-#define MAX_MATRIX_SIZE 81
+namespace arm_compute
+{
+namespace
+{
+constexpr unsigned int max_matrix_size = 81;
+} // namespace
 
 /****************************************************************************************\
  *                                 Square Convolution                                *
@@ -138,8 +141,8 @@
     // Set build options
     std::set<std::string> build_opts;
 
-    int16_t mat[matrix_size * matrix_size] = { 0 };
-    memcpy(mat, conv, matrix_size * sizeof(int16_t));
+    std::array<int16_t, matrix_size *matrix_size> mat = { 0 };
+    memcpy(mat.data(), conv, matrix_size * sizeof(int16_t));
 
     for(unsigned int j = 0; j < matrix_size * matrix_size; j++)
     {
@@ -173,7 +176,7 @@
 template <unsigned int matrix_size>
 BorderSize             CLSeparableConvolutionVertKernel<matrix_size>::border_size() const
 {
-    return BorderSize(matrix_size / 2, 0);
+    return BorderSize{ matrix_size / 2, 0 };
 }
 
 template <unsigned int matrix_size>
@@ -190,8 +193,8 @@
 
     std::set<std::string> build_opts;
 
-    int16_t mat[matrix_size * matrix_size] = { 0 };
-    memcpy(mat + matrix_size, conv, matrix_size * sizeof(int16_t));
+    std::array<int16_t, matrix_size *matrix_size> mat = { 0 };
+    memcpy(mat.data() + matrix_size, conv, matrix_size * sizeof(int16_t));
 
     for(unsigned int j = 0; j < matrix_size * matrix_size; j++)
     {
@@ -264,11 +267,11 @@
 
     uint32_t matrix_size = width * height;
 
-    int16_t mat[MAX_MATRIX_SIZE] = { 0 };
+    std::array<int16_t, max_matrix_size> mat = { 0 };
 
-    memcpy(mat, conv, matrix_size * sizeof(int16_t));
+    memcpy(mat.data(), conv, matrix_size * sizeof(int16_t));
 
-    for(unsigned int j = 0; j < MAX_MATRIX_SIZE; j++)
+    for(unsigned int j = 0; j < max_matrix_size; j++)
     {
         options.insert("-DMAT" + support::cpp11::to_string(j) + "=" + support::cpp11::to_string(mat[j]));
     }
@@ -328,3 +331,4 @@
 template class arm_compute::CLSeparableConvolutionHorKernel<5>;
 template class arm_compute::CLSeparableConvolutionHorKernel<7>;
 template class arm_compute::CLSeparableConvolutionHorKernel<9>;
+} // namespace arm_compute
diff --git a/src/core/utils/helpers/tensor_transform.cpp b/src/core/utils/helpers/tensor_transform.cpp
index 08803c7..7c56390 100644
--- a/src/core/utils/helpers/tensor_transform.cpp
+++ b/src/core/utils/helpers/tensor_transform.cpp
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2018 ARM Limited.
+ * Copyright (c) 2018-2019 ARM Limited.
  *
  * SPDX-License-Identifier: MIT
  *
@@ -114,7 +114,9 @@
                                                                                  Coordinates starts, Coordinates ends, Coordinates strides,
                                                                                  int32_t begin_mask, int32_t end_mask, int32_t shrink_axis_mask)
 {
-    Coordinates starts_abs, ends_abs, final_strides;
+    Coordinates starts_abs{};
+    Coordinates ends_abs{};
+    Coordinates final_strides{};
     for(unsigned int i = 0; i < input_shape.num_dimensions(); ++i)
     {
         const int start_i = calculate_start_on_index(input_shape, i, starts, strides, begin_mask);
diff --git a/src/core/utils/logging/LoggerRegistry.cpp b/src/core/utils/logging/LoggerRegistry.cpp
index 99236d2..3a46696 100644
--- a/src/core/utils/logging/LoggerRegistry.cpp
+++ b/src/core/utils/logging/LoggerRegistry.cpp
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2017 ARM Limited.
+ * Copyright (c) 2017-2019 ARM Limited.
  *
  * SPDX-License-Identifier: MIT
  *
@@ -66,7 +66,7 @@
     return (_loggers.find(name) != _loggers.end()) ? _loggers[name] : nullptr;
 }
 
-void LoggerRegistry::create_reserved_loggers(LogLevel log_level, std::vector<std::shared_ptr<Printer>> printers)
+void LoggerRegistry::create_reserved_loggers(LogLevel log_level, const std::vector<std::shared_ptr<Printer>> &printers)
 {
     std::lock_guard<arm_compute::Mutex> lock(_mtx);
     for(const auto &r : _reserved_loggers)
diff --git a/src/core/utils/quantization/AsymmHelpers.cpp b/src/core/utils/quantization/AsymmHelpers.cpp
index ea9ba77..d606adb 100644
--- a/src/core/utils/quantization/AsymmHelpers.cpp
+++ b/src/core/utils/quantization/AsymmHelpers.cpp
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2017-2018 ARM Limited.
+ * Copyright (c) 2017-2019 ARM Limited.
  *
  * SPDX-License-Identifier: MIT
  *
@@ -29,12 +29,12 @@
 
 using namespace arm_compute::quantization;
 
-constexpr int64_t fixed_point_one_Q0 = (1ll << 31);
+constexpr int64_t fixed_point_one_Q0 = (1LL << 31);
 constexpr float   epsilon            = 0.00001f;
 
 arm_compute::Status arm_compute::quantization::calculate_quantized_multiplier_less_than_one(float multiplier,
-                                                                                            int   *quant_multiplier,
-                                                                                            int   *right_shift)
+                                                                                            int *quant_multiplier,
+                                                                                            int *right_shift)
 {
     ARM_COMPUTE_RETURN_ERROR_ON(quant_multiplier == nullptr);
     ARM_COMPUTE_RETURN_ERROR_ON(right_shift == nullptr);
@@ -71,8 +71,8 @@
 }
 
 arm_compute::Status arm_compute::quantization::calculate_quantized_multiplier_greater_than_one(float multiplier,
-                                                                                               int   *quantized_multiplier,
-                                                                                               int   *left_shift)
+                                                                                               int *quantized_multiplier,
+                                                                                               int *left_shift)
 {
     ARM_COMPUTE_RETURN_ERROR_ON(quantized_multiplier == nullptr);
     ARM_COMPUTE_RETURN_ERROR_ON(left_shift == nullptr);
diff --git a/src/graph/Graph.cpp b/src/graph/Graph.cpp
index 88e2682..9d437b1 100644
--- a/src/graph/Graph.cpp
+++ b/src/graph/Graph.cpp
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2018 ARM Limited.
+ * Copyright (c) 2018-2019 ARM Limited.
  *
  * SPDX-License-Identifier: MIT
  *
@@ -152,7 +152,7 @@
     return true;
 }
 
-TensorID Graph::create_tensor(TensorDescriptor desc)
+TensorID Graph::create_tensor(const TensorDescriptor &desc)
 {
     TensorID tid    = _tensors.size();
     auto     tensor = support::cpp14::make_unique<Tensor>(tid, desc);
diff --git a/src/graph/GraphBuilder.cpp b/src/graph/GraphBuilder.cpp
index 9f8dd69..5db9540 100644
--- a/src/graph/GraphBuilder.cpp
+++ b/src/graph/GraphBuilder.cpp
@@ -30,15 +30,19 @@
 
 #include "support/ToolchainSupport.h"
 
-#define CHECK_NODEIDX_PAIR(pair, g) \
-    ARM_COMPUTE_ERROR_ON(((pair).node_id >= (g).nodes().size()) || ((g).node((pair).node_id) == nullptr) || ((pair).index >= (g).node((pair).node_id)->num_outputs()));
-
 namespace arm_compute
 {
 namespace graph
 {
 namespace
 {
+inline void check_nodeidx_pair(const NodeIdxPair &pair, const Graph &g)
+{
+    ARM_COMPUTE_UNUSED(pair);
+    ARM_COMPUTE_UNUSED(g);
+    ARM_COMPUTE_ERROR_ON((pair.node_id >= g.nodes().size()) || (g.node((pair).node_id) == nullptr) || (pair.index >= g.node(pair.node_id)->num_outputs()));
+}
+
 Status set_node_params(Graph &g, NodeID nid, NodeParams &params)
 {
     INode *node = g.node(nid);
@@ -62,10 +66,10 @@
     return Status{};
 }
 
-NodeID add_const_node_with_name(Graph &g, NodeParams params, const std::string &name, TensorDescriptor desc, ITensorAccessorUPtr accessor)
+NodeID add_const_node_with_name(Graph &g, NodeParams params, const std::string &name, const TensorDescriptor &desc, ITensorAccessorUPtr accessor)
 {
     params.name = params.name.empty() ? "" : params.name + name;
-    auto nid    = GraphBuilder::add_const_node(g, params, std::move(desc), std::move(accessor));
+    auto nid    = GraphBuilder::add_const_node(g, params, desc, std::move(accessor));
     set_node_params(g, nid, params);
     return nid;
 }
@@ -73,7 +77,7 @@
 template <typename NT, typename... Args>
 NodeID create_simple_single_input_output_node(Graph &g, NodeParams &params, NodeIdxPair input, Args &&... args)
 {
-    CHECK_NODEIDX_PAIR(input, g);
+    check_nodeidx_pair(input, g);
 
     NodeID nid = g.add_node<NT>(std::forward<Args>(args)...);
     g.add_connection(input.node_id, input.index, nid, 0);
@@ -83,7 +87,7 @@
 }
 
 template <typename NT, typename... Args>
-NodeID create_simple_multiple_input_single_output_node(Graph &g, NodeParams &params, std::vector<NodeIdxPair> inputs, Args &&... args)
+NodeID create_simple_multiple_input_single_output_node(Graph &g, NodeParams &params, const std::vector<NodeIdxPair> &inputs, Args &&... args)
 {
     ARM_COMPUTE_ERROR_ON(inputs.size() == 0);
 
@@ -92,7 +96,7 @@
     unsigned int i = 0;
     for(const auto &input : inputs)
     {
-        CHECK_NODEIDX_PAIR(input, g);
+        check_nodeidx_pair(input, g);
         g.add_connection(input.node_id, input.index, nid, i++);
     }
     set_node_params(g, nid, params);
@@ -101,7 +105,7 @@
 }
 } // namespace
 
-NodeID GraphBuilder::add_const_node(Graph &g, NodeParams params, TensorDescriptor desc, ITensorAccessorUPtr accessor)
+NodeID GraphBuilder::add_const_node(Graph &g, NodeParams params, const TensorDescriptor &desc, ITensorAccessorUPtr accessor)
 {
     auto nid = g.add_node<ConstNode>(desc);
     set_node_params(g, nid, params);
@@ -109,7 +113,7 @@
     return nid;
 }
 
-NodeID GraphBuilder::add_input_node(Graph &g, NodeParams params, TensorDescriptor desc, ITensorAccessorUPtr accessor)
+NodeID GraphBuilder::add_input_node(Graph &g, NodeParams params, const TensorDescriptor &desc, ITensorAccessorUPtr accessor)
 {
     auto nid = g.add_node<InputNode>(desc);
     set_node_params(g, nid, params);
@@ -119,7 +123,7 @@
 
 NodeID GraphBuilder::add_output_node(Graph &g, NodeParams params, NodeIdxPair input, ITensorAccessorUPtr accessor)
 {
-    CHECK_NODEIDX_PAIR(input, g);
+    check_nodeidx_pair(input, g);
 
     NodeID nid = g.add_node<OutputNode>();
     g.add_connection(input.node_id, input.index, nid, 0);
@@ -139,7 +143,7 @@
                                                   ITensorAccessorUPtr mean_accessor, ITensorAccessorUPtr var_accessor,
                                                   ITensorAccessorUPtr beta_accessor, ITensorAccessorUPtr gamma_accessor)
 {
-    CHECK_NODEIDX_PAIR(input, g);
+    check_nodeidx_pair(input, g);
 
     bool has_beta  = (beta_accessor != nullptr);
     bool has_gamma = (gamma_accessor != nullptr);
@@ -189,8 +193,8 @@
 
 NodeID GraphBuilder::add_bounding_box_transform_node(Graph &g, NodeParams params, NodeIdxPair input, NodeIdxPair deltas, BoundingBoxTransformInfo info)
 {
-    CHECK_NODEIDX_PAIR(input, g);
-    CHECK_NODEIDX_PAIR(deltas, g);
+    check_nodeidx_pair(input, g);
+    check_nodeidx_pair(deltas, g);
 
     NodeID nid = g.add_node<BoundingBoxTransformLayerNode>(info);
 
@@ -213,7 +217,7 @@
                                           const QuantizationInfo weights_quant_info,
                                           const QuantizationInfo out_quant_info)
 {
-    CHECK_NODEIDX_PAIR(input, g);
+    check_nodeidx_pair(input, g);
     ARM_COMPUTE_ERROR_ON(depth == 0);
     ARM_COMPUTE_ERROR_ON((kernel_spatial_extend.width == 0) || (kernel_spatial_extend.height == 0));
 
@@ -268,7 +272,7 @@
                                             Size2D inner_border, ITensorAccessorUPtr weights_accessor,
                                             ITensorAccessorUPtr bias_accessor)
 {
-    CHECK_NODEIDX_PAIR(input, g);
+    check_nodeidx_pair(input, g);
     ARM_COMPUTE_ERROR_ON(depth == 0);
     ARM_COMPUTE_ERROR_ON((kernel_spatial_extend.width == 0) || (kernel_spatial_extend.height == 0));
 
@@ -323,7 +327,7 @@
                                                     PadStrideInfo conv_info, int depth_multiplier, DepthwiseConvolutionMethod method,
                                                     ITensorAccessorUPtr weights_accessor, ITensorAccessorUPtr bias_accessor, const QuantizationInfo quant_info, const QuantizationInfo out_quant_info)
 {
-    CHECK_NODEIDX_PAIR(input, g);
+    check_nodeidx_pair(input, g);
     ARM_COMPUTE_ERROR_ON((kernel_spatial_extend.width == 0) || (kernel_spatial_extend.height == 0));
 
     bool has_bias = (bias_accessor != nullptr);
@@ -374,9 +378,9 @@
 }
 NodeID GraphBuilder::add_detection_output_node(Graph &g, NodeParams params, NodeIdxPair input_loc, NodeIdxPair input_conf, NodeIdxPair input_priorbox, const DetectionOutputLayerInfo &detect_info)
 {
-    CHECK_NODEIDX_PAIR(input_loc, g);
-    CHECK_NODEIDX_PAIR(input_conf, g);
-    CHECK_NODEIDX_PAIR(input_priorbox, g);
+    check_nodeidx_pair(input_loc, g);
+    check_nodeidx_pair(input_conf, g);
+    check_nodeidx_pair(input_priorbox, g);
 
     // Create detection_output node and connect
     NodeID detect_nid = g.add_node<DetectionOutputLayerNode>(detect_info);
@@ -396,8 +400,8 @@
 
 NodeID GraphBuilder::add_elementwise_node(Graph &g, NodeParams params, NodeIdxPair input0, NodeIdxPair input1, EltwiseOperation operation)
 {
-    CHECK_NODEIDX_PAIR(input0, g);
-    CHECK_NODEIDX_PAIR(input1, g);
+    check_nodeidx_pair(input0, g);
+    check_nodeidx_pair(input1, g);
 
     NodeID nid = g.add_node<EltwiseLayerNode>(operation);
 
@@ -418,7 +422,7 @@
                                                NodeID weights_nid, NodeID bias_nid,
                                                const FullyConnectedLayerInfo fc_info, const QuantizationInfo out_quant_info)
 {
-    CHECK_NODEIDX_PAIR(input, g);
+    check_nodeidx_pair(input, g);
     ARM_COMPUTE_ERROR_ON(num_outputs == 0);
     ARM_COMPUTE_ERROR_ON(weights_nid == EmptyNodeID);
 
@@ -446,7 +450,7 @@
                                                const FullyConnectedLayerInfo fc_info,
                                                const QuantizationInfo weights_quant_info, const QuantizationInfo out_quant_info)
 {
-    CHECK_NODEIDX_PAIR(input, g);
+    check_nodeidx_pair(input, g);
     ARM_COMPUTE_ERROR_ON(num_outputs == 0);
 
     bool has_bias = (bias_accessor != nullptr);
@@ -487,9 +491,9 @@
 
 NodeID GraphBuilder::add_generate_proposals_node(Graph &g, NodeParams params, NodeIdxPair scores, NodeIdxPair deltas, NodeIdxPair anchors, GenerateProposalsInfo info)
 {
-    CHECK_NODEIDX_PAIR(scores, g);
-    CHECK_NODEIDX_PAIR(deltas, g);
-    CHECK_NODEIDX_PAIR(anchors, g);
+    check_nodeidx_pair(scores, g);
+    check_nodeidx_pair(deltas, g);
+    check_nodeidx_pair(anchors, g);
 
     NodeID nid = g.add_node<GenerateProposalsLayerNode>(info);
 
@@ -509,7 +513,7 @@
 NodeID GraphBuilder::add_normalize_planar_yuv_node(Graph &g, NodeParams params, NodeIdxPair input,
                                                    ITensorAccessorUPtr mean_accessor, ITensorAccessorUPtr std_accessor)
 {
-    CHECK_NODEIDX_PAIR(input, g);
+    check_nodeidx_pair(input, g);
 
     // Get input tensor descriptor
     const TensorDescriptor input_tensor_desc = get_tensor_descriptor(g, g.node(input.node_id)->outputs()[0]);
@@ -549,8 +553,8 @@
 
 NodeID GraphBuilder::add_priorbox_node(Graph &g, NodeParams params, NodeIdxPair input0, NodeIdxPair input1, const PriorBoxLayerInfo &prior_info)
 {
-    CHECK_NODEIDX_PAIR(input0, g);
-    CHECK_NODEIDX_PAIR(input1, g);
+    check_nodeidx_pair(input0, g);
+    check_nodeidx_pair(input1, g);
 
     // Create priorbox node and connect
     NodeID prior_nid = g.add_node<PriorBoxLayerNode>(prior_info);
@@ -580,8 +584,8 @@
 
 NodeID GraphBuilder::add_roi_align_node(Graph &g, NodeParams params, NodeIdxPair input, NodeIdxPair rois, ROIPoolingLayerInfo pool_info)
 {
-    CHECK_NODEIDX_PAIR(input, g);
-    CHECK_NODEIDX_PAIR(rois, g);
+    check_nodeidx_pair(input, g);
+    check_nodeidx_pair(rois, g);
 
     NodeID nid = g.add_node<ROIAlignLayerNode>(pool_info);
 
@@ -594,7 +598,7 @@
 
 NodeID GraphBuilder::add_scale_layer(Graph &g, const NodeParams &params, NodeIdxPair input, ITensorAccessorUPtr mul_accessor, ITensorAccessorUPtr add_accessor)
 {
-    CHECK_NODEIDX_PAIR(input, g);
+    check_nodeidx_pair(input, g);
 
     // Get input tensor descriptor
     const TensorDescriptor input_tensor_desc = get_tensor_descriptor(g, g.node(input.node_id)->outputs()[0]);
diff --git a/src/graph/Tensor.cpp b/src/graph/Tensor.cpp
index 9850128..205ef11 100644
--- a/src/graph/Tensor.cpp
+++ b/src/graph/Tensor.cpp
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2018 ARM Limited.
+ * Copyright (c) 2018-2019 ARM Limited.
  *
  * SPDX-License-Identifier: MIT
  *
@@ -108,7 +108,7 @@
     _bound_edges.erase(eid);
 }
 
-const std::set<EdgeID> Tensor::bound_edges() const
+std::set<EdgeID> Tensor::bound_edges() const
 {
     return _bound_edges;
 }
diff --git a/src/graph/detail/CrossLayerMemoryManagerHelpers.cpp b/src/graph/detail/CrossLayerMemoryManagerHelpers.cpp
index 7fc5ca0..5e31309 100644
--- a/src/graph/detail/CrossLayerMemoryManagerHelpers.cpp
+++ b/src/graph/detail/CrossLayerMemoryManagerHelpers.cpp
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2018 ARM Limited.
+ * Copyright (c) 2018-2019 ARM Limited.
  *
  * SPDX-License-Identifier: MIT
  *
@@ -136,7 +136,7 @@
             // Then add it to the list of transition buffers
             ITensorHandle *tensor_handle = input_edge->tensor()->handle()->parent_handle();
             IMemoryGroup *mm_group      = get_memory_group_from_handle(ctx, tensor_handle);
-            transition_handles.input_handles.push_back(std::make_pair(tensor_handle, mm_group));
+            transition_handles.input_handles.emplace_back(std::make_pair(tensor_handle, mm_group));
         }
     }
 
@@ -149,7 +149,7 @@
         {
             ITensorHandle *tensor_handle = output_tensor->handle()->parent_handle();
             IMemoryGroup *mm_group      = get_memory_group_from_handle(ctx, tensor_handle);
-            transition_handles.output_handles.push_back(std::make_pair(tensor_handle, mm_group));
+            transition_handles.output_handles.emplace_back(std::make_pair(tensor_handle, mm_group));
         }
     }
 
diff --git a/src/graph/mutators/NodeFusionMutator.cpp b/src/graph/mutators/NodeFusionMutator.cpp
index b28f2db..427d7b5 100644
--- a/src/graph/mutators/NodeFusionMutator.cpp
+++ b/src/graph/mutators/NodeFusionMutator.cpp
@@ -207,7 +207,7 @@
     const std::set<Activation> supported_fused_activations = { Activation::RELU, Activation::BOUNDED_RELU, Activation::LU_BOUNDED_RELU };
 
     // Preconditions
-    auto empty_prec = [](INode & n)
+    auto empty_prec = [](INode &)
     {
         return true;
     };
diff --git a/src/graph/nodes/ConcatenateLayerNode.cpp b/src/graph/nodes/ConcatenateLayerNode.cpp
index ff515c4..5f13b90 100644
--- a/src/graph/nodes/ConcatenateLayerNode.cpp
+++ b/src/graph/nodes/ConcatenateLayerNode.cpp
@@ -72,6 +72,7 @@
 
     // Extract shapes
     std::vector<const TensorShape *> shapes;
+    shapes.reserve(input_descriptors.size());
     for(auto &input_descriptor : input_descriptors)
     {
         shapes.emplace_back(&input_descriptor.shape);
diff --git a/src/runtime/GLES_COMPUTE/functions/GCDepthConcatenateLayer.cpp b/src/runtime/GLES_COMPUTE/functions/GCDepthConcatenateLayer.cpp
index aa937a6..b89aafa 100755
--- a/src/runtime/GLES_COMPUTE/functions/GCDepthConcatenateLayer.cpp
+++ b/src/runtime/GLES_COMPUTE/functions/GCDepthConcatenateLayer.cpp
@@ -47,13 +47,18 @@
 
     unsigned int depth_offset = 0;
 
-    _concat_kernels_vector  = arm_compute::support::cpp14::make_unique<GCDepthConcatenateLayerKernel[]>(_num_inputs);
-    _border_handlers_vector = arm_compute::support::cpp14::make_unique<GCFillBorderKernel[]>(_num_inputs);
+    _concat_kernels_vector.reserve(_num_inputs);
+    _border_handlers_vector.reserve(_num_inputs);
 
     for(unsigned int i = 0; i < _num_inputs; i++)
     {
-        _concat_kernels_vector[i].configure(inputs_vector.at(i), depth_offset, output);
-        _border_handlers_vector[i].configure(inputs_vector.at(i), _concat_kernels_vector[i].border_size(), BorderMode::CONSTANT, PixelValue());
+        auto concat_kernel = support::cpp14::make_unique<GCDepthConcatenateLayerKernel>();
+        auto border_kernel = support::cpp14::make_unique<GCFillBorderKernel>();
+
+        concat_kernel->configure(inputs_vector.at(i), depth_offset, output);
+        border_kernel->configure(inputs_vector.at(i), concat_kernel->border_size(), BorderMode::CONSTANT, PixelValue());
+        _concat_kernels_vector.emplace_back(std::move(concat_kernel));
+        _border_handlers_vector.emplace_back(std::move(border_kernel));
 
         depth_offset += inputs_vector.at(i)->info()->dimension(2);
     }
@@ -63,8 +68,8 @@
 {
     for(unsigned i = 0; i < _num_inputs; i++)
     {
-        GCScheduler::get().dispatch(_border_handlers_vector[i], false);
+        GCScheduler::get().dispatch(*_border_handlers_vector[i].get(), false);
         GCScheduler::get().memory_barrier();
-        GCScheduler::get().dispatch(_concat_kernels_vector[i], true);
+        GCScheduler::get().dispatch(*_concat_kernels_vector[i].get(), true);
     }
 }
diff --git a/src/runtime/NEON/functions/NECropResize.cpp b/src/runtime/NEON/functions/NECropResize.cpp
index 4360b50..cc39d02 100644
--- a/src/runtime/NEON/functions/NECropResize.cpp
+++ b/src/runtime/NEON/functions/NECropResize.cpp
@@ -30,7 +30,7 @@
 namespace arm_compute
 {
 NECropResize::NECropResize()
-    : _output(nullptr), _num_boxes(0), _method(), _extrapolation_value(0), _crop(), _scale()
+    : _output(nullptr), _num_boxes(0), _method(), _extrapolation_value(0), _crop(), _scale(), _crop_results(), _scaled_results()
 {
 }
 
@@ -70,22 +70,31 @@
     // - A scale function is used to resize the cropped image to the size specified by crop_size.
     // - A tensor is required to hold the final scaled image before it is copied into the 4D output
     //   that will hold all final cropped and scaled 3D images.
-    _crop           = arm_compute::support::cpp14::make_unique<NECropKernel[]>(_num_boxes);
-    _crop_results   = arm_compute::support::cpp14::make_unique<Tensor[]>(_num_boxes);
-    _scale          = arm_compute::support::cpp14::make_unique<NEScale[]>(_num_boxes);
-    _scaled_results = arm_compute::support::cpp14::make_unique<Tensor[]>(_num_boxes);
+    _crop.reserve(_num_boxes);
+    _crop_results.reserve(_num_boxes);
+    _scaled_results.reserve(_num_boxes);
+    _scale.reserve(_num_boxes);
 
     for(unsigned int i = 0; i < _num_boxes; ++i)
     {
+        auto       crop_tensor = support::cpp14::make_unique<Tensor>();
         TensorInfo crop_result_info(1, DataType::F32);
         crop_result_info.set_data_layout(DataLayout::NHWC);
-        _crop_results[i].allocator()->init(crop_result_info);
+        crop_tensor->allocator()->init(crop_result_info);
 
+        auto       scale_tensor = support::cpp14::make_unique<Tensor>();
         TensorInfo scaled_result_info(out_shape, 1, DataType::F32);
         scaled_result_info.set_data_layout(DataLayout::NHWC);
-        _scaled_results[i].allocator()->init(scaled_result_info);
+        scale_tensor->allocator()->init(scaled_result_info);
 
-        _crop[i].configure(input, boxes, box_ind, &_crop_results[i], i, _extrapolation_value);
+        auto crop_kernel  = support::cpp14::make_unique<NECropKernel>();
+        auto scale_kernel = support::cpp14::make_unique<NEScale>();
+        crop_kernel->configure(input, boxes, box_ind, crop_tensor.get(), i, _extrapolation_value);
+
+        _crop.emplace_back(std::move(crop_kernel));
+        _scaled_results.emplace_back(std::move(scale_tensor));
+        _crop_results.emplace_back(std::move(crop_tensor));
+        _scale.emplace_back(std::move(scale_kernel));
     }
 }
 
@@ -97,17 +106,17 @@
     {
         // Size of the crop box in _boxes and thus the shape of _crop_results[i]
         // may not be known until run-time and so the kernels cannot be configured until then.
-        _crop[i].configure_output_shape();
-        _crop_results[i].allocator()->allocate();
-        NEScheduler::get().schedule(&_crop[i], Window::DimZ);
+        _crop[i]->configure_output_shape();
+        _crop_results[i]->allocator()->allocate();
+        NEScheduler::get().schedule(_crop[i].get(), Window::DimZ);
 
         // Scale the cropped image.
-        _scale[i].configure(&_crop_results[i], &_scaled_results[i], _method, BorderMode::CONSTANT, PixelValue(_extrapolation_value), SamplingPolicy::TOP_LEFT, false);
-        _scaled_results[i].allocator()->allocate();
-        _scale[i].run();
+        _scale[i]->configure(_crop_results[i].get(), _scaled_results[i].get(), _method, BorderMode::CONSTANT, PixelValue(_extrapolation_value), SamplingPolicy::TOP_LEFT, false);
+        _scaled_results[i]->allocator()->allocate();
+        _scale[i]->run();
 
         // Copy scaled image into output.
-        std::copy_n(_scaled_results[i].buffer(), _scaled_results[i].info()->total_size(), _output->ptr_to_element(Coordinates(0, 0, 0, i)));
+        std::copy_n(_scaled_results[i]->buffer(), _scaled_results[i]->info()->total_size(), _output->ptr_to_element(Coordinates(0, 0, 0, i)));
     }
 }
 } // namespace arm_compute
\ No newline at end of file
diff --git a/src/runtime/NEON/functions/NEDepthConcatenateLayer.cpp b/src/runtime/NEON/functions/NEDepthConcatenateLayer.cpp
index b814bff..8f070a2 100644
--- a/src/runtime/NEON/functions/NEDepthConcatenateLayer.cpp
+++ b/src/runtime/NEON/functions/NEDepthConcatenateLayer.cpp
@@ -45,9 +45,7 @@
 
 void NEDepthConcatenateLayer::configure(const std::vector<ITensor *> &inputs_vector, ITensor *output) // NOLINT
 {
-    _num_inputs             = inputs_vector.size();
-    _concat_kernels_vector  = arm_compute::support::cpp14::make_unique<NEDepthConcatenateLayerKernel[]>(_num_inputs);
-    _border_handlers_vector = arm_compute::support::cpp14::make_unique<NEFillBorderKernel[]>(_num_inputs);
+    _num_inputs = inputs_vector.size();
 
     std::vector<ITensorInfo *> inputs_vector_info;
     for(unsigned int i = 0; i < _num_inputs; i++)
@@ -61,10 +59,16 @@
     ARM_COMPUTE_ERROR_THROW_ON(NEDepthConcatenateLayer::validate(inputs_vector_info, output->info()));
 
     unsigned int depth_offset = 0;
+    _concat_kernels_vector.reserve(_num_inputs);
+    _border_handlers_vector.reserve(_num_inputs);
     for(unsigned int i = 0; i < _num_inputs; ++i)
     {
-        _concat_kernels_vector[i].configure(inputs_vector.at(i), depth_offset, output);
-        _border_handlers_vector[i].configure(inputs_vector.at(i), _concat_kernels_vector[i].border_size(), BorderMode::CONSTANT, PixelValue(static_cast<float>(0.f)));
+        auto concat_kernel = support::cpp14::make_unique<NEDepthConcatenateLayerKernel>();
+        auto border_kernel = support::cpp14::make_unique<NEFillBorderKernel>();
+        concat_kernel->configure(inputs_vector.at(i), depth_offset, output);
+        border_kernel->configure(inputs_vector.at(i), concat_kernel->border_size(), BorderMode::CONSTANT, PixelValue(static_cast<float>(0.f)));
+        _border_handlers_vector.emplace_back(std::move(border_kernel));
+        _concat_kernels_vector.emplace_back(std::move(concat_kernel));
 
         depth_offset += inputs_vector.at(i)->info()->dimension(2);
     }
@@ -98,7 +102,7 @@
 {
     for(unsigned i = 0; i < _num_inputs; ++i)
     {
-        NEScheduler::get().schedule(&_border_handlers_vector[i], Window::DimX);
-        NEScheduler::get().schedule(&_concat_kernels_vector[i], Window::DimX);
+        NEScheduler::get().schedule(_border_handlers_vector[i].get(), Window::DimX);
+        NEScheduler::get().schedule(_concat_kernels_vector[i].get(), Window::DimX);
     }
 }
diff --git a/src/runtime/NEON/functions/NEGaussianPyramid.cpp b/src/runtime/NEON/functions/NEGaussianPyramid.cpp
index 8a85bba..0dbcb12 100644
--- a/src/runtime/NEON/functions/NEGaussianPyramid.cpp
+++ b/src/runtime/NEON/functions/NEGaussianPyramid.cpp
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2016, 2017 ARM Limited.
+ * Copyright (c) 2016-2019 ARM Limited.
  *
  * SPDX-License-Identifier: MIT
  *
@@ -74,11 +74,6 @@
 
     if(num_levels > 1)
     {
-        _horizontal_border_handler = arm_compute::support::cpp14::make_unique<NEFillBorderKernel[]>(num_levels - 1);
-        _vertical_border_handler   = arm_compute::support::cpp14::make_unique<NEFillBorderKernel[]>(num_levels - 1);
-        _horizontal_reduction      = arm_compute::support::cpp14::make_unique<NEGaussianPyramidHorKernel[]>(num_levels - 1);
-        _vertical_reduction        = arm_compute::support::cpp14::make_unique<NEGaussianPyramidVertKernel[]>(num_levels - 1);
-
         // Apply half scale to the X dimension of the tensor shape
         TensorShape tensor_shape = pyramid->info()->tensor_shape();
         tensor_shape.set(0, (pyramid->info()->width() + 1) * SCALE_PYRAMID_HALF);
@@ -86,19 +81,33 @@
         PyramidInfo pyramid_info(num_levels - 1, SCALE_PYRAMID_HALF, tensor_shape, Format::S16);
         _tmp.init(pyramid_info);
 
+        _horizontal_reduction.reserve(num_levels);
+        _vertical_reduction.reserve(num_levels);
+        _horizontal_border_handler.reserve(num_levels);
+        _vertical_border_handler.reserve(num_levels);
+
         for(unsigned int i = 0; i < num_levels - 1; ++i)
         {
             /* Configure horizontal kernel */
-            _horizontal_reduction[i].configure(_pyramid->get_pyramid_level(i), _tmp.get_pyramid_level(i));
+            auto horizontal_kernel = support::cpp14::make_unique<NEGaussianPyramidHorKernel>();
+            horizontal_kernel->configure(_pyramid->get_pyramid_level(i), _tmp.get_pyramid_level(i));
 
             /* Configure vertical kernel */
-            _vertical_reduction[i].configure(_tmp.get_pyramid_level(i), _pyramid->get_pyramid_level(i + 1));
+            auto vertical_kernel = support::cpp14::make_unique<NEGaussianPyramidVertKernel>();
+            vertical_kernel->configure(_tmp.get_pyramid_level(i), _pyramid->get_pyramid_level(i + 1));
 
             /* Configure border */
-            _horizontal_border_handler[i].configure(_pyramid->get_pyramid_level(i), _horizontal_reduction[i].border_size(), border_mode, PixelValue(constant_border_value));
+            auto horizontal_border_kernel = support::cpp14::make_unique<NEFillBorderKernel>();
+            horizontal_border_kernel->configure(_pyramid->get_pyramid_level(i), horizontal_kernel->border_size(), border_mode, PixelValue(constant_border_value));
 
             /* Configure border */
-            _vertical_border_handler[i].configure(_tmp.get_pyramid_level(i), _vertical_reduction[i].border_size(), border_mode, PixelValue(pixel_value_u16));
+            auto vertical_border_kernel = support::cpp14::make_unique<NEFillBorderKernel>();
+            vertical_border_kernel->configure(_tmp.get_pyramid_level(i), vertical_kernel->border_size(), border_mode, PixelValue(pixel_value_u16));
+
+            _vertical_border_handler.emplace_back(std::move(vertical_border_kernel));
+            _horizontal_border_handler.emplace_back(std::move(horizontal_border_kernel));
+            _vertical_reduction.emplace_back(std::move(vertical_kernel));
+            _horizontal_reduction.emplace_back(std::move(horizontal_kernel));
         }
 
         _tmp.allocate();
@@ -117,10 +126,10 @@
 
     for(unsigned int i = 0; i < num_levels - 1; ++i)
     {
-        NEScheduler::get().schedule(_horizontal_border_handler.get() + i, Window::DimZ);
-        NEScheduler::get().schedule(_horizontal_reduction.get() + i, Window::DimY);
-        NEScheduler::get().schedule(_vertical_border_handler.get() + i, Window::DimZ);
-        NEScheduler::get().schedule(_vertical_reduction.get() + i, Window::DimY);
+        NEScheduler::get().schedule(_horizontal_border_handler[i].get(), Window::DimZ);
+        NEScheduler::get().schedule(_horizontal_reduction[i].get(), Window::DimY);
+        NEScheduler::get().schedule(_vertical_border_handler[i].get(), Window::DimZ);
+        NEScheduler::get().schedule(_vertical_reduction[i].get(), Window::DimY);
     }
 }
 
@@ -147,19 +156,20 @@
 
     if(num_levels > 1)
     {
-        _gaus5x5       = arm_compute::support::cpp14::make_unique<NEGaussian5x5[]>(num_levels - 1);
-        _scale_nearest = arm_compute::support::cpp14::make_unique<NEScale[]>(num_levels - 1);
-
         PyramidInfo pyramid_info(num_levels - 1, SCALE_PYRAMID_ORB, pyramid->info()->tensor_shape(), Format::U8);
         _tmp.init(pyramid_info);
 
         for(unsigned int i = 0; i < num_levels - 1; ++i)
         {
             /* Configure gaussian 5x5 */
-            _gaus5x5[i].configure(_pyramid->get_pyramid_level(i), _tmp.get_pyramid_level(i), border_mode, constant_border_value);
+            auto gaus5x5_kernel = support::cpp14::make_unique<NEGaussian5x5>();
+            gaus5x5_kernel->configure(_pyramid->get_pyramid_level(i), _tmp.get_pyramid_level(i), border_mode, constant_border_value);
+            _gaus5x5.emplace_back(std::move(gaus5x5_kernel));
 
             /* Configure scale */
-            _scale_nearest[i].configure(_tmp.get_pyramid_level(i), _pyramid->get_pyramid_level(i + 1), InterpolationPolicy::NEAREST_NEIGHBOR, BorderMode::UNDEFINED);
+            auto scale_kernel = support::cpp14::make_unique<NEScale>();
+            scale_kernel->configure(_tmp.get_pyramid_level(i), _pyramid->get_pyramid_level(i + 1), InterpolationPolicy::NEAREST_NEIGHBOR, BorderMode::UNDEFINED);
+            _scale_nearest.emplace_back(std::move(scale_kernel));
         }
 
         _tmp.allocate();
@@ -178,7 +188,7 @@
 
     for(unsigned int i = 0; i < num_levels - 1; ++i)
     {
-        _gaus5x5[i].run();
-        _scale_nearest[i].run();
+        _gaus5x5[i].get()->run();
+        _scale_nearest[i].get()->run();
     }
 }
diff --git a/src/runtime/NEON/functions/NEHOGMultiDetection.cpp b/src/runtime/NEON/functions/NEHOGMultiDetection.cpp
index 6a6d045..26abc9d 100644
--- a/src/runtime/NEON/functions/NEHOGMultiDetection.cpp
+++ b/src/runtime/NEON/functions/NEHOGMultiDetection.cpp
@@ -126,12 +126,12 @@
     _num_block_norm_kernel  = input_block_norm.size(); // Number of NEHOGBlockNormalizationKernel kernels to compute
     _num_hog_detect_kernel  = input_hog_detect.size(); // Number of NEHOGDetector functions to compute
 
-    _orient_bin_kernel = arm_compute::support::cpp14::make_unique<NEHOGOrientationBinningKernel[]>(_num_orient_bin_kernel);
-    _block_norm_kernel = arm_compute::support::cpp14::make_unique<NEHOGBlockNormalizationKernel[]>(_num_block_norm_kernel);
-    _hog_detect_kernel = arm_compute::support::cpp14::make_unique<NEHOGDetector[]>(_num_hog_detect_kernel);
+    _orient_bin_kernel.reserve(_num_orient_bin_kernel);
+    _block_norm_kernel.reserve(_num_block_norm_kernel);
+    _hog_detect_kernel.reserve(_num_hog_detect_kernel);
+    _hog_space.reserve(_num_orient_bin_kernel);
+    _hog_norm_space.reserve(_num_block_norm_kernel);
     _non_maxima_kernel = arm_compute::support::cpp14::make_unique<CPPDetectionWindowNonMaximaSuppressionKernel>();
-    _hog_space         = arm_compute::support::cpp14::make_unique<Tensor[]>(_num_orient_bin_kernel);
-    _hog_norm_space    = arm_compute::support::cpp14::make_unique<Tensor[]>(_num_block_norm_kernel);
 
     // Allocate tensors for magnitude and phase
     TensorInfo info_mag(shape_img, Format::S16);
@@ -167,13 +167,17 @@
 
         // Allocate HOG space
         TensorInfo info_space(shape_hog_space, num_bins, DataType::F32);
-        _hog_space[i].allocator()->init(info_space);
+        auto       hog_space_tensor = support::cpp14::make_unique<Tensor>();
+        hog_space_tensor->allocator()->init(info_space);
 
         // Manage intermediate buffers
-        _memory_group.manage(_hog_space.get() + i);
+        _memory_group.manage(hog_space_tensor.get());
 
         // Initialise orientation binning kernel
-        _orient_bin_kernel[i].configure(&_mag, &_phase, _hog_space.get() + i, multi_hog->model(idx_multi_hog)->info());
+        auto orient_bin_kernel = support::cpp14::make_unique<NEHOGOrientationBinningKernel>();
+        orient_bin_kernel->configure(&_mag, &_phase, hog_space_tensor.get(), multi_hog->model(idx_multi_hog)->info());
+        _orient_bin_kernel.emplace_back(std::move(orient_bin_kernel));
+        _hog_space.emplace_back(std::move(hog_space_tensor));
     }
 
     // Allocate intermediate tensors
@@ -188,19 +192,23 @@
 
         // Allocate normalized HOG space
         TensorInfo tensor_info(*(multi_hog->model(idx_multi_hog)->info()), width, height);
-        _hog_norm_space[i].allocator()->init(tensor_info);
+        auto       hog_norm_space_tensor = support::cpp14::make_unique<Tensor>();
+        hog_norm_space_tensor->allocator()->init(tensor_info);
 
         // Manage intermediate buffers
-        _memory_group.manage(_hog_norm_space.get() + i);
+        _memory_group.manage(hog_norm_space_tensor.get());
 
         // Initialize block normalization kernel
-        _block_norm_kernel[i].configure(_hog_space.get() + idx_orient_bin, _hog_norm_space.get() + i, multi_hog->model(idx_multi_hog)->info());
+        auto block_norm_kernel = support::cpp14::make_unique<NEHOGBlockNormalizationKernel>();
+        block_norm_kernel->configure(_hog_space[idx_orient_bin].get(), hog_norm_space_tensor.get(), multi_hog->model(idx_multi_hog)->info());
+        _block_norm_kernel.emplace_back(std::move(block_norm_kernel));
+        _hog_norm_space.emplace_back(std::move(hog_norm_space_tensor));
     }
 
     // Allocate intermediate tensors
     for(size_t i = 0; i < _num_orient_bin_kernel; ++i)
     {
-        _hog_space[i].allocator()->allocate();
+        _hog_space[i].get()->allocator()->allocate();
     }
 
     // Configure HOG detector kernel
@@ -208,7 +216,9 @@
     {
         const size_t idx_block_norm = input_hog_detect[i];
 
-        _hog_detect_kernel[i].configure(_hog_norm_space.get() + idx_block_norm, multi_hog->model(i), detection_windows, detection_window_strides->at(i), threshold, i);
+        auto hog_detect_kernel = support::cpp14::make_unique<NEHOGDetector>();
+        hog_detect_kernel->configure(_hog_norm_space[idx_block_norm].get(), multi_hog->model(i), detection_windows, detection_window_strides->at(i), threshold, i);
+        _hog_detect_kernel.emplace_back(std::move(hog_detect_kernel));
     }
 
     // Configure non maxima suppression kernel
@@ -217,7 +227,7 @@
     // Allocate intermediate tensors
     for(size_t i = 0; i < _num_block_norm_kernel; ++i)
     {
-        _hog_norm_space[i].allocator()->allocate();
+        _hog_norm_space[i]->allocator()->allocate();
     }
 }
 
@@ -234,21 +244,21 @@
     _gradient_kernel.run();
 
     // Run orientation binning kernel
-    for(size_t i = 0; i < _num_orient_bin_kernel; ++i)
+    for(auto &kernel : _orient_bin_kernel)
     {
-        NEScheduler::get().schedule(_orient_bin_kernel.get() + i, Window::DimY);
+        NEScheduler::get().schedule(kernel.get(), Window::DimY);
     }
 
     // Run block normalization kernel
-    for(size_t i = 0; i < _num_block_norm_kernel; ++i)
+    for(auto &kernel : _block_norm_kernel)
     {
-        NEScheduler::get().schedule(_block_norm_kernel.get() + i, Window::DimY);
+        NEScheduler::get().schedule(kernel.get(), Window::DimY);
     }
 
     // Run HOG detector kernel
-    for(size_t i = 0; i < _num_hog_detect_kernel; ++i)
+    for(auto &kernel : _hog_detect_kernel)
     {
-        _hog_detect_kernel[i].run();
+        kernel->run();
     }
 
     // Run non-maxima suppression kernel if enabled
diff --git a/src/runtime/NEON/functions/NEOpticalFlow.cpp b/src/runtime/NEON/functions/NEOpticalFlow.cpp
index db77629..0df01c6 100644
--- a/src/runtime/NEON/functions/NEOpticalFlow.cpp
+++ b/src/runtime/NEON/functions/NEOpticalFlow.cpp
@@ -74,10 +74,10 @@
 
     const float pyr_scale = old_pyramid->info()->scale();
 
-    _func_scharr    = arm_compute::support::cpp14::make_unique<NEScharr3x3[]>(_num_levels);
-    _kernel_tracker = arm_compute::support::cpp14::make_unique<NELKTrackerKernel[]>(_num_levels);
-    _scharr_gx      = arm_compute::support::cpp14::make_unique<Tensor[]>(_num_levels);
-    _scharr_gy      = arm_compute::support::cpp14::make_unique<Tensor[]>(_num_levels);
+    _func_scharr.reserve(_num_levels);
+    _kernel_tracker.reserve(_num_levels);
+    _scharr_gx.reserve(_num_levels);
+    _scharr_gy.reserve(_num_levels);
 
     _old_points_internal = LKInternalKeypointArray(old_points->num_values());
     _new_points_internal = LKInternalKeypointArray(old_points->num_values());
@@ -95,25 +95,34 @@
 
         TensorInfo tensor_info(TensorShape(width_ith, height_ith), Format::S16);
 
-        _scharr_gx[i].allocator()->init(tensor_info);
-        _scharr_gy[i].allocator()->init(tensor_info);
+        auto scharr_gx = support::cpp14::make_unique<Tensor>();
+        auto scharr_gy = support::cpp14::make_unique<Tensor>();
+        scharr_gx->allocator()->init(tensor_info);
+        scharr_gy->allocator()->init(tensor_info);
 
         // Manage intermediate buffers
-        _memory_group.manage(_scharr_gx.get() + i);
-        _memory_group.manage(_scharr_gy.get() + i);
+        _memory_group.manage(scharr_gx.get());
+        _memory_group.manage(scharr_gy.get());
 
         // Init Scharr kernel
-        _func_scharr[i].configure(old_ith_input, _scharr_gx.get() + i, _scharr_gy.get() + i, border_mode, constant_border_value);
+        auto func_scharr = support::cpp14::make_unique<NEScharr3x3>();
+        func_scharr->configure(old_ith_input, scharr_gx.get(), scharr_gy.get(), border_mode, constant_border_value);
 
         // Init Lucas-Kanade kernel
-        _kernel_tracker[i].configure(old_ith_input, new_ith_input, _scharr_gx.get() + i, _scharr_gy.get() + i,
-                                     old_points, new_points_estimates, new_points,
-                                     &_old_points_internal, &_new_points_internal,
-                                     termination, use_initial_estimate, epsilon, num_iterations, window_dimension,
-                                     i, _num_levels, pyr_scale);
+        auto kernel_tracker = support::cpp14::make_unique<NELKTrackerKernel>();
+        kernel_tracker->configure(old_ith_input, new_ith_input, scharr_gx.get(), scharr_gy.get(),
+                                  old_points, new_points_estimates, new_points,
+                                  &_old_points_internal, &_new_points_internal,
+                                  termination, use_initial_estimate, epsilon, num_iterations, window_dimension,
+                                  i, _num_levels, pyr_scale);
 
-        _scharr_gx[i].allocator()->allocate();
-        _scharr_gy[i].allocator()->allocate();
+        scharr_gx->allocator()->allocate();
+        scharr_gy->allocator()->allocate();
+
+        _func_scharr.emplace_back(std::move(func_scharr));
+        _kernel_tracker.emplace_back(std::move(kernel_tracker));
+        _scharr_gx.emplace_back(std::move(scharr_gx));
+        _scharr_gy.emplace_back(std::move(scharr_gy));
     }
 }
 
@@ -126,9 +135,9 @@
     for(unsigned int level = _num_levels; level > 0; --level)
     {
         // Run Scharr kernel
-        _func_scharr[level - 1].run();
+        _func_scharr[level - 1].get()->run();
 
         // Run Lucas-Kanade kernel
-        NEScheduler::get().schedule(_kernel_tracker.get() + level - 1, Window::DimX);
+        NEScheduler::get().schedule(_kernel_tracker[level - 1].get(), Window::DimX);
     }
 }
diff --git a/tests/validate_examples/graph_fully_connected.cpp b/tests/validate_examples/graph_fully_connected.cpp
index 085518c..dfa15ed 100644
--- a/tests/validate_examples/graph_fully_connected.cpp
+++ b/tests/validate_examples/graph_fully_connected.cpp
@@ -142,6 +142,7 @@
     /** Default destructor */
     ~FullyConnectedOptions() override = default;
 
+private:
     SimpleOption<int>      *width;              /**< Input width */
     SimpleOption<int>      *batch;              /**< Input batch */
     SimpleOption<float>    *input_scale;        /**< Input Quantization scale from QASSYMM8 */
diff --git a/tests/validation/NEON/Convolution.cpp b/tests/validation/NEON/Convolution.cpp
index 3a9f29c..b942ddc 100644
--- a/tests/validation/NEON/Convolution.cpp
+++ b/tests/validation/NEON/Convolution.cpp
@@ -66,14 +66,14 @@
     Tensor dst = create_tensor<Tensor>(shape, output_data_type);
 
     // Create conv matrix
-    int16_t conv[9] = {};
+    std::array<int16_t, 9> conv = { 0 };
 
     ARM_COMPUTE_EXPECT(src.info()->is_resizable(), framework::LogLevel::ERRORS);
     ARM_COMPUTE_EXPECT(dst.info()->is_resizable(), framework::LogLevel::ERRORS);
 
     // Create and configure function
     NEConvolution3x3 convolution;
-    convolution.configure(&src, &dst, conv, 0, border_mode);
+    convolution.configure(&src, &dst, conv.data(), 0, border_mode);
 
     // Validate valid region
     const ValidRegion dst_valid_region = shape_to_valid_region(shape, (border_mode == BorderMode::UNDEFINED), BorderSize(filter_size / 2));
@@ -134,14 +134,14 @@
     Tensor dst = create_tensor<Tensor>(shape, output_data_type);
 
     // Create conv matrix
-    int16_t conv[25] = {};
+    std::array<int16_t, 25> conv = { 0 };
 
     ARM_COMPUTE_EXPECT(src.info()->is_resizable(), framework::LogLevel::ERRORS);
     ARM_COMPUTE_EXPECT(dst.info()->is_resizable(), framework::LogLevel::ERRORS);
 
     // Create and configure function
     NEConvolution5x5 convolution;
-    convolution.configure(&src, &dst, conv, 0, border_mode);
+    convolution.configure(&src, &dst, conv.data(), 0, border_mode);
 
     // Validate valid region
     const ValidRegion dst_valid_region = shape_to_valid_region(shape, (border_mode == BorderMode::UNDEFINED), BorderSize(filter_size / 2));
@@ -202,14 +202,14 @@
     Tensor dst = create_tensor<Tensor>(shape, output_data_type);
 
     // Create conv matrix
-    int16_t conv[49] = {};
+    std::array<int16_t, 49> conv = { 0 };
 
     ARM_COMPUTE_EXPECT(src.info()->is_resizable(), framework::LogLevel::ERRORS);
     ARM_COMPUTE_EXPECT(dst.info()->is_resizable(), framework::LogLevel::ERRORS);
 
     // Create and configure function
     NEConvolution7x7 convolution;
-    convolution.configure(&src, &dst, conv, 0, border_mode);
+    convolution.configure(&src, &dst, conv.data(), 0, border_mode);
 
     // Validate valid region
     const ValidRegion dst_valid_region = shape_to_valid_region(shape, (border_mode == BorderMode::UNDEFINED), BorderSize(filter_size / 2));
@@ -270,14 +270,14 @@
     Tensor dst = create_tensor<Tensor>(shape, output_data_type);
 
     // Create conv matrix
-    int16_t conv[81] = {};
+    std::array<int16_t, 81> conv = { 0 };
 
     ARM_COMPUTE_EXPECT(src.info()->is_resizable(), framework::LogLevel::ERRORS);
     ARM_COMPUTE_EXPECT(dst.info()->is_resizable(), framework::LogLevel::ERRORS);
 
     // Create and configure function
     NEConvolution9x9 convolution;
-    convolution.configure(&src, &dst, conv, 0, border_mode);
+    convolution.configure(&src, &dst, conv.data(), 0, border_mode);
 
     // Validate valid region
     const ValidRegion dst_valid_region = shape_to_valid_region(shape, (border_mode == BorderMode::UNDEFINED), BorderSize(filter_size / 2));