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