From 48e84c8f77e85bb9bdeb2a631cc9cf2fad37a4a0 Mon Sep 17 00:00:00 2001 From: Daniel Koch Date: Thu, 1 Sep 2016 14:55:50 -0600 Subject: [PATCH] Cleanup --- include/mavrosflight/param.h | 9 --------- src/mavrosflight/param.cpp | 31 ------------------------------- 2 files changed, 40 deletions(-) diff --git a/include/mavrosflight/param.h b/include/mavrosflight/param.h index 0b71763..a1de25c 100644 --- a/include/mavrosflight/param.h +++ b/include/mavrosflight/param.h @@ -29,16 +29,9 @@ class Param MAV_PARAM_TYPE getType() const; double getValue() const; - void setName(std::string name); - void setIndex(int index); - void setType(MAV_PARAM_TYPE type); - void setValue(double value); - void requestSet(double value, mavlink_message_t *msg); bool handleUpdate(const mavlink_param_value_t &msg); - YAML::Node toYaml(); - private: void init(std::string name, int index, MAV_PARAM_TYPE type, float raw_value); @@ -79,8 +72,6 @@ class Param float expected_raw_value_; }; -YAML::Emitter& operator << (YAML::Emitter& out, const Param& param); - } // namespace mavrosflight #endif // MAVROSFLIGHT_PARAM_H diff --git a/src/mavrosflight/param.cpp b/src/mavrosflight/param.cpp index 9a4d54f..e4d252d 100644 --- a/src/mavrosflight/param.cpp +++ b/src/mavrosflight/param.cpp @@ -50,26 +50,6 @@ double Param::getValue() const return value_; } -void Param::setName(std::string name) -{ - name_ = name; -} - -void Param::setIndex(int index) -{ - index_ = index; -} - -void Param::setType(MAV_PARAM_TYPE type) -{ - type_ = type; -} - -void Param::setValue(double value) -{ - value_ = value; -} - void Param::requestSet(double value, mavlink_message_t *msg) { if (value != value_) @@ -104,17 +84,6 @@ bool Param::handleUpdate(const mavlink_param_value_t &msg) return false; } -YAML::Node Param::toYaml() -{ - YAML::Node node; - node["name"] = name_; - node["index"] = index_; - node["type"] = (int) type_; - node["value"] = value_; - - return node; -} - void Param::init(std::string name, int index, MAV_PARAM_TYPE type, float raw_value) { name_ = name;