param.h
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 
37 #ifndef MAVROSFLIGHT_PARAM_H
38 #define MAVROSFLIGHT_PARAM_H
39 
42 
43 #include <yaml-cpp/yaml.h>
44 
45 namespace mavrosflight
46 {
47 class Param
48 {
49 public:
50  Param();
52  Param(std::string name, int index, MAV_PARAM_TYPE type, float raw_value);
53 
54  uint16_t pack_param_set_msg(uint8_t system,
55  uint8_t component,
56  mavlink_message_t *msg,
57  uint8_t target_system,
58  uint8_t target_component);
59 
60  std::string getName() const;
61  int getIndex() const;
62  MAV_PARAM_TYPE getType() const;
63  double getValue() const;
64 
65  void requestSet(double value, mavlink_message_t *msg);
66  bool handleUpdate(const mavlink_param_value_t &msg);
67 
68 private:
69  void init(std::string name, int index, MAV_PARAM_TYPE type, float raw_value);
70 
71  void setFromRawValue(float raw_value);
72  float getRawValue();
73  float getRawValue(double value);
74  double getCastValue(double value);
75 
76  template <typename T>
77  double fromRawValue(float value)
78  {
79  T t_value = *(T *)&value;
80  return (double)t_value;
81  }
82 
83  template <typename T>
84  float toRawValue(double value)
85  {
86  T t_value = (T)value;
87  return *(float *)&t_value;
88  }
89 
90  template <typename T>
91  double toCastValue(double value)
92  {
93  return (double)((T)value);
94  }
95 
97 
98  std::string name_;
99  int index_;
101  double value_;
102 
104  double new_value_;
106 };
107 
108 } // namespace mavrosflight
109 
110 #endif // MAVROSFLIGHT_PARAM_H
void setFromRawValue(float raw_value)
Definition: param.cpp:122
MAV_PARAM_TYPE
Definition: common.h:508
double getValue() const
Definition: param.cpp:75
float getRawValue()
Definition: param.cpp:150
double new_value_
Definition: param.h:104
MavlinkSerial * serial_
Definition: param.h:96
int getIndex() const
Definition: param.cpp:65
float toRawValue(double value)
Definition: param.h:84
bool set_in_progress_
Definition: param.h:103
double toCastValue(double value)
Definition: param.h:91
float expected_raw_value_
Definition: param.h:105
uint16_t pack_param_set_msg(uint8_t system, uint8_t component, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component)
void requestSet(double value, mavlink_message_t *msg)
Definition: param.cpp:80
std::string getName() const
Definition: param.cpp:60
double fromRawValue(float value)
Definition: param.h:77
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