37 #ifndef MAVROSFLIGHT_PARAM_H 38 #define MAVROSFLIGHT_PARAM_H 43 #include <yaml-cpp/yaml.h> 56 uint8_t target_system, uint8_t target_component);
63 void requestSet(
double value, mavlink_message_t *msg);
77 T t_value = *(T*) &value;
78 return (
double) t_value;
84 T t_value = (T) value;
85 return *(
float*) &t_value;
91 return (
double) ((T) value);
108 #endif // MAVROSFLIGHT_PARAM_H void setFromRawValue(float raw_value)
float toRawValue(double value)
double toCastValue(double value)
float expected_raw_value_
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)
std::string getName() const
double fromRawValue(float value)
MAV_PARAM_TYPE getType() const
bool handleUpdate(const mavlink_param_value_t &msg)
double getCastValue(double value)
void init(std::string name, int index, MAV_PARAM_TYPE type, float raw_value)