PX4 Firmware
PX4 Autopilot Software http://px4.io
mavlink_simple_analyzer.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2018 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file mavlink_simple_analyzer.h
36  *
37  * @author Achermann Florian <acfloria@ethz.ch>
38  */
39 
40 #pragma once
41 
42 #include <float.h>
43 #include <stdint.h>
44 
45 /**
46  * SimpleAnalyzer
47  *
48  * Class used for simple analysis of data streams.
49  * The data can be analyzed in the following three modes:
50  *
51  * AVERAGE:
52  * The average value is computed at the beginning. Based on the number of analyzed values,
53  * the update rate and the window size the switch to the moving average is determined.
54  *
55  * MIN:
56  * The minimum value is tracked.
57  *
58  * MAX:
59  * The maximum value is tracked.
60  */
62 {
63 public:
64  enum Mode {
65  AVERAGE = 0,
66  MIN,
67  MAX,
68  };
69 
70  /**
71  * Constructor
72  *
73  * Defines the mode of the analyzer and the window size in case of the
74  * averaging mode.
75  *
76  * @param[in] mode: The mode of the analyzer
77  * @param[in] window: The window size in seconds. Only used in the averaging mode.
78  */
79  SimpleAnalyzer(Mode mode, float window = 60.0f);
80 
81  /**
82  * Reset the analyzer to the initial state.
83  */
84  void reset();
85 
86  /**
87  * Add a new value to the analyzer and update the result according to the mode.
88  *
89  * @param[in] val: The value to process
90  * @param[in] update_rate: The update rate in [1/s] for which new value are added.
91  * Used in the averaging mode to determine when to switch from averaging to the moving average.
92  */
93  void add_value(float val, float update_rate);
94 
95  /**
96  * Returns true if at least one value has been added to the analyzer.
97  */
98  bool valid() const;
99 
100  /**
101  * Get the current result of the analyzer.
102  */
103  float get() const;
104 
105  /**
106  * Get the scaled value of the current result of the analyzer.
107  *
108  * @param[in] scalingfactor: The factor used to scale the result.
109  */
110  float get_scaled(float scalingfactor) const;
111 
112  /**
113  * Get the rounded scaled value casted to the input template type.
114  * Should only be used to return integer types.
115  *
116  * @param[out] ret: The scaled and rounded value of the current analyzer result.
117  * @parma[in] scalingfactor: The factor which is used to scale the result.
118  */
119  void get_scaled(uint8_t &ret, float scalingfactor) const
120  {
121  float avg = get_scaled(scalingfactor);
122  int_round(avg);
123  check_limits(avg, 0, UINT8_MAX);
124 
125  ret = static_cast<uint8_t>(avg);
126  }
127 
128  void get_scaled(int8_t &ret, float scalingfactor) const
129  {
130  float avg = get_scaled(scalingfactor);
131  int_round(avg);
132  check_limits(avg, INT8_MIN, INT8_MAX);
133 
134  ret = static_cast<int8_t>(avg);
135  }
136 
137 private:
138  unsigned int _n = 0; /**< The number of added samples */
139  float _window = 60.0f; /**< The window size for the moving average filter [s] */
140  Mode _mode = AVERAGE; /**< The mode of the simple analyzer */
141  float _result = 0.0f; /**< The result of the analyzed data. */
142 
143  void check_limits(float &x, float min, float max) const;
144  void int_round(float &x) const;
145 };
146 
147 void convert_limit_safe(float in, uint16_t &out);
148 void convert_limit_safe(float in, int16_t &out);
SimpleAnalyzer.
SimpleAnalyzer(Mode mode, float window=60.0f)
Constructor.
void get_scaled(int8_t &ret, float scalingfactor) const
void reset()
Reset the analyzer to the initial state.
void get_scaled(uint8_t &ret, float scalingfactor) const
Get the rounded scaled value casted to the input template type.
float get_scaled(float scalingfactor) const
Get the scaled value of the current result of the analyzer.
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
void check_limits(float &x, float min, float max) const
constexpr _Tp min(_Tp a, _Tp b)
Definition: Limits.hpp:54
bool valid() const
Returns true if at least one value has been added to the analyzer.
constexpr _Tp max(_Tp a, _Tp b)
Definition: Limits.hpp:60
unsigned int _n
The number of added samples.
void int_round(float &x) const
mode
Definition: vtol_type.h:76
float _result
The result of the analyzed data.
void add_value(float val, float update_rate)
Add a new value to the analyzer and update the result according to the mode.
Mode _mode
The mode of the simple analyzer.
float _window
The window size for the moving average filter [s].