param.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab.
3  * 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 are met:
7  *
8  * * Redistributions of source code must retain the above copyright notice, this
9  * list of conditions and the following disclaimer.
10  *
11  * * Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * * Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived from
17  * this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
38 
39 namespace mavrosflight
40 {
42 {
43  init("", -1, MAV_PARAM_TYPE_ENUM_END, 0.0f);
44 }
45 
47 {
51 
52  init(std::string(name), msg.param_index, (MAV_PARAM_TYPE)msg.param_type, msg.param_value);
53 }
54 
55 Param::Param(std::string name, int index, MAV_PARAM_TYPE type, float raw_value)
56 {
57  init(name, index, type, raw_value);
58 }
59 
60 std::string Param::getName() const
61 {
62  return name_;
63 }
64 
65 int Param::getIndex() const
66 {
67  return index_;
68 }
69 
71 {
72  return type_;
73 }
74 
75 double Param::getValue() const
76 {
77  return value_;
78 }
79 
80 void Param::requestSet(double value, mavlink_message_t *msg)
81 {
82  if (value != value_)
83  {
84  new_value_ = getCastValue(value);
86 
88 
89  set_in_progress_ = true;
90  }
91 }
92 
94 {
95  if (msg.param_index != index_)
96  return false;
97 
98  if (msg.param_type != type_)
99  return false;
100 
102  set_in_progress_ = false;
103 
104  if (msg.param_value != getRawValue())
105  {
107  return true;
108  }
109 
110  return false;
111 }
112 
113 void Param::init(std::string name, int index, MAV_PARAM_TYPE type, float raw_value)
114 {
115  name_ = name;
116  index_ = index;
117  type_ = type;
118  setFromRawValue(raw_value);
119  set_in_progress_ = false;
120 }
121 
122 void Param::setFromRawValue(float raw_value)
123 {
124  switch (type_)
125  {
126  case MAV_PARAM_TYPE_INT8:
127  value_ = fromRawValue<int8_t>(raw_value);
128  break;
130  value_ = fromRawValue<int16_t>(raw_value);
131  break;
133  value_ = fromRawValue<int32_t>(raw_value);
134  break;
136  value_ = fromRawValue<uint8_t>(raw_value);
137  break;
139  value_ = fromRawValue<uint16_t>(raw_value);
140  break;
142  value_ = fromRawValue<uint32_t>(raw_value);
143  break;
145  value_ = fromRawValue<float>(raw_value);
146  break;
147  }
148 }
149 
151 {
152  return getRawValue(value_);
153 }
154 
155 float Param::getRawValue(double value)
156 {
157  float raw_value;
158 
159  switch (type_)
160  {
161  case MAV_PARAM_TYPE_INT8:
162  raw_value = toRawValue<int8_t>(value);
163  break;
165  raw_value = toRawValue<int16_t>(value);
166  break;
168  raw_value = toRawValue<int32_t>(value);
169  break;
171  raw_value = toRawValue<uint8_t>(value);
172  break;
174  raw_value = toRawValue<uint16_t>(value);
175  break;
177  raw_value = toRawValue<uint32_t>(value);
178  break;
180  raw_value = toRawValue<float>(value);
181  break;
182  }
183 
184  return raw_value;
185 }
186 
187 double Param::getCastValue(double value)
188 {
189  double cast_value;
190 
191  switch (type_)
192  {
193  case MAV_PARAM_TYPE_INT8:
194  cast_value = toCastValue<int8_t>(value);
195  break;
197  cast_value = toCastValue<int16_t>(value);
198  break;
200  cast_value = toCastValue<int32_t>(value);
201  break;
203  cast_value = toCastValue<uint8_t>(value);
204  break;
206  cast_value = toCastValue<uint16_t>(value);
207  break;
209  cast_value = toCastValue<uint32_t>(value);
210  break;
212  cast_value = toCastValue<float>(value);
213  break;
214  }
215 
216  return cast_value;
217 }
218 
219 } // namespace mavrosflight
void setFromRawValue(float raw_value)
Definition: param.cpp:122
MAV_PARAM_TYPE
Definition: common.h:508
f
double getValue() const
Definition: param.cpp:75
float getRawValue()
Definition: param.cpp:150
double new_value_
Definition: param.h:104
int getIndex() const
Definition: param.cpp:65
bool set_in_progress_
Definition: param.h:103
float expected_raw_value_
Definition: param.h:105
void requestSet(double value, mavlink_message_t *msg)
Definition: param.cpp:80
std::string getName() const
Definition: param.cpp:60
MAV_PARAM_TYPE getType() const
Definition: param.cpp:70
bool handleUpdate(const mavlink_param_value_t &msg)
Definition: param.cpp:93
double getCastValue(double value)
Definition: param.cpp:187
MAV_PARAM_TYPE type_
Definition: param.h:100
std::string name_
Definition: param.h:98
void init(std::string name, int index, MAV_PARAM_TYPE type, float raw_value)
Definition: param.cpp:113


rosflight
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:09:26