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 {
41 
43 {
44  init("", -1, MAV_PARAM_TYPE_ENUM_END, 0.0f);
45 }
46 
48 {
52 
53  init(std::string(name),
54  msg.param_index,
56  msg.param_value);
57 }
58 
59 Param::Param(std::string name, int index, MAV_PARAM_TYPE type, float raw_value)
60 {
61  init(name, index, type, raw_value);
62 }
63 
64 std::string Param::getName() const
65 {
66  return name_;
67 }
68 
69 int Param::getIndex() const
70 {
71  return index_;
72 }
73 
75 {
76  return type_;
77 }
78 
79 double Param::getValue() const
80 {
81  return value_;
82 }
83 
84 void Param::requestSet(double value, mavlink_message_t *msg)
85 {
86  if (value != value_)
87  {
88  new_value_ = getCastValue(value);
90 
91  mavlink_msg_param_set_pack(1, 50, msg,
93 
94  set_in_progress_ = true;
95  }
96 }
97 
99 {
100  if (msg.param_index != index_)
101  return false;
102 
103  if (msg.param_type != type_)
104  return false;
105 
107  set_in_progress_ = false;
108 
109  if (msg.param_value != getRawValue())
110  {
112  return true;
113  }
114 
115  return false;
116 }
117 
118 void Param::init(std::string name, int index, MAV_PARAM_TYPE type, float raw_value)
119 {
120  name_ = name;
121  index_ = index;
122  type_ = type;
123  setFromRawValue(raw_value);
124  set_in_progress_ = false;
125 }
126 
127 void Param::setFromRawValue(float raw_value)
128 {
129  switch (type_)
130  {
131  case MAV_PARAM_TYPE_INT8:
132  value_ = fromRawValue<int8_t>(raw_value);
133  break;
135  value_ = fromRawValue<int16_t>(raw_value);
136  break;
138  value_ = fromRawValue<int32_t>(raw_value);
139  break;
141  value_ = fromRawValue<uint8_t>(raw_value);
142  break;
144  value_ = fromRawValue<uint16_t>(raw_value);
145  break;
147  value_ = fromRawValue<uint32_t>(raw_value);
148  break;
150  value_ = fromRawValue<float>(raw_value);
151  break;
152  }
153 }
154 
156 {
157  return getRawValue(value_);
158 }
159 
160 float Param::getRawValue(double value)
161 {
162  float raw_value;
163 
164  switch (type_)
165  {
166  case MAV_PARAM_TYPE_INT8:
167  raw_value = toRawValue<int8_t>(value);
168  break;
170  raw_value = toRawValue<int16_t>(value);
171  break;
173  raw_value = toRawValue<int32_t>(value);
174  break;
176  raw_value = toRawValue<uint8_t>(value);
177  break;
179  raw_value = toRawValue<uint16_t>(value);
180  break;
182  raw_value = toRawValue<uint32_t>(value);
183  break;
185  raw_value = toRawValue<float>(value);
186  break;
187  }
188 
189  return raw_value;
190 }
191 
192 double Param::getCastValue(double value)
193 {
194  double cast_value;
195 
196  switch (type_)
197  {
198  case MAV_PARAM_TYPE_INT8:
199  cast_value = toCastValue<int8_t>(value);
200  break;
202  cast_value = toCastValue<int16_t>(value);
203  break;
205  cast_value = toCastValue<int32_t>(value);
206  break;
208  cast_value = toCastValue<uint8_t>(value);
209  break;
211  cast_value = toCastValue<uint16_t>(value);
212  break;
214  cast_value = toCastValue<uint32_t>(value);
215  break;
217  cast_value = toCastValue<float>(value);
218  break;
219  }
220 
221  return cast_value;
222 }
223 
224 } // namespace mavrosflight
void setFromRawValue(float raw_value)
Definition: param.cpp:127
MAV_PARAM_TYPE
Definition: common.h:508
f
double getValue() const
Definition: param.cpp:79
float getRawValue()
Definition: param.cpp:155
double new_value_
Definition: param.h:102
int getIndex() const
Definition: param.cpp:69
bool set_in_progress_
Definition: param.h:101
float expected_raw_value_
Definition: param.h:103
void requestSet(double value, mavlink_message_t *msg)
Definition: param.cpp:84
std::string getName() const
Definition: param.cpp:64
double value_
Definition: param.h:99
MAV_PARAM_TYPE getType() const
Definition: param.cpp:74
bool handleUpdate(const mavlink_param_value_t &msg)
Definition: param.cpp:98
double getCastValue(double value)
Definition: param.cpp:192
MAV_PARAM_TYPE type_
Definition: param.h:98
std::string name_
Definition: param.h:96
void init(std::string name, int index, MAV_PARAM_TYPE type, float raw_value)
Definition: param.cpp:118


rosflight
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 20:00:13