Firmware
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 
40 #pragma once
41 
42 #include <float.h>
43 #include <stdint.h>
44 
62 {
63 public:
64  enum Mode {
65  AVERAGE = 0,
66  MIN,
67  MAX,
68  };
69 
79  SimpleAnalyzer(Mode mode, float window = 60.0f);
80 
84  void reset();
85 
93  void add_value(float val, float update_rate);
94 
98  bool valid() const;
99 
103  float get() const;
104 
110  float get_scaled(float scalingfactor) const;
111 
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;
139  float _window = 60.0f;
140  Mode _mode = AVERAGE;
141  float _result = 0.0f;
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);
void reset()
Reset the analyzer to the initial state.
Definition: mavlink_simple_analyzer.cpp:54
SimpleAnalyzer.
Definition: mavlink_simple_analyzer.h:61
void get_scaled(uint8_t &ret, float scalingfactor) const
Get the rounded scaled value casted to the input template type.
Definition: mavlink_simple_analyzer.h:119
float get_scaled(float scalingfactor) const
Get the scaled value of the current result of the analyzer.
Definition: mavlink_simple_analyzer.cpp:125
bool valid() const
Returns true if at least one value has been added to the analyzer.
Definition: mavlink_simple_analyzer.cpp:115
SimpleAnalyzer(Mode mode, float window=60.0f)
Constructor.
Definition: mavlink_simple_analyzer.cpp:47
void add_value(float val, float update_rate)
Add a new value to the analyzer and update the result according to the mode.
Definition: mavlink_simple_analyzer.cpp:79