aboutsummaryrefslogtreecommitdiff
path: root/src/modules/controllib
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-10-10 21:15:03 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-10-10 21:15:03 +0200
commit44deeb85c09451865c7d869f495a31f1b4348fec (patch)
tree4022df1d50a5d9b2d5cbbc05c5e56289965fc25a /src/modules/controllib
parent0cb8e782b0e2a6ca0dde4fac641e863c95d04511 (diff)
downloadpx4-firmware-44deeb85c09451865c7d869f495a31f1b4348fec.tar.gz
px4-firmware-44deeb85c09451865c7d869f495a31f1b4348fec.tar.bz2
px4-firmware-44deeb85c09451865c7d869f495a31f1b4348fec.zip
We compile with GCC 4.7.4
Diffstat (limited to 'src/modules/controllib')
-rw-r--r--src/modules/controllib/block/BlockParam.hpp29
-rw-r--r--src/modules/controllib/blocks.hpp36
2 files changed, 41 insertions, 24 deletions
diff --git a/src/modules/controllib/block/BlockParam.hpp b/src/modules/controllib/block/BlockParam.hpp
index 58a9bfc0d..36bc8c24b 100644
--- a/src/modules/controllib/block/BlockParam.hpp
+++ b/src/modules/controllib/block/BlockParam.hpp
@@ -69,22 +69,39 @@ protected:
/**
* Parameters that are tied to blocks for updating and nameing.
*/
-template<class T>
-class __EXPORT BlockParam : public BlockParamBase
+
+class __EXPORT BlockParamFloat : public BlockParamBase
+{
+public:
+ BlockParamFloat(Block *block, const char *name, bool parent_prefix=true) :
+ BlockParamBase(block, name, parent_prefix),
+ _val() {
+ update();
+ }
+ float get() { return _val; }
+ void set(float val) { _val = val; }
+ void update() {
+ if (_handle != PARAM_INVALID) param_get(_handle, &_val);
+ }
+protected:
+ float _val;
+};
+
+class __EXPORT BlockParamInt : public BlockParamBase
{
public:
- BlockParam(Block *block, const char *name, bool parent_prefix=true) :
+ BlockParamInt(Block *block, const char *name, bool parent_prefix=true) :
BlockParamBase(block, name, parent_prefix),
_val() {
update();
}
- T get() { return _val; }
- void set(T val) { _val = val; }
+ int get() { return _val; }
+ void set(int val) { _val = val; }
void update() {
if (_handle != PARAM_INVALID) param_get(_handle, &_val);
}
protected:
- T _val;
+ int _val;
};
} // namespace control
diff --git a/src/modules/controllib/blocks.hpp b/src/modules/controllib/blocks.hpp
index fefe99702..66e929038 100644
--- a/src/modules/controllib/blocks.hpp
+++ b/src/modules/controllib/blocks.hpp
@@ -74,8 +74,8 @@ public:
float getMax() { return _max.get(); }
protected:
// attributes
- BlockParam<float> _min;
- BlockParam<float> _max;
+ control::BlockParamFloat _min;
+ control::BlockParamFloat _max;
};
int __EXPORT blockLimitTest();
@@ -99,7 +99,7 @@ public:
float getMax() { return _max.get(); }
protected:
// attributes
- BlockParam<float> _max;
+ control::BlockParamFloat _max;
};
int __EXPORT blockLimitSymTest();
@@ -126,7 +126,7 @@ public:
protected:
// attributes
float _state;
- BlockParam<float> _fCut;
+ control::BlockParamFloat _fCut;
};
int __EXPORT blockLowPassTest();
@@ -157,7 +157,7 @@ protected:
// attributes
float _u; /**< previous input */
float _y; /**< previous output */
- BlockParam<float> _fCut; /**< cut-off frequency, Hz */
+ control::BlockParamFloat _fCut; /**< cut-off frequency, Hz */
};
int __EXPORT blockHighPassTest();
@@ -273,7 +273,7 @@ public:
// accessors
float getKP() { return _kP.get(); }
protected:
- BlockParam<float> _kP;
+ control::BlockParamFloat _kP;
};
int __EXPORT blockPTest();
@@ -303,8 +303,8 @@ public:
BlockIntegral &getIntegral() { return _integral; }
private:
BlockIntegral _integral;
- BlockParam<float> _kP;
- BlockParam<float> _kI;
+ control::BlockParamFloat _kP;
+ control::BlockParamFloat _kI;
};
int __EXPORT blockPITest();
@@ -334,8 +334,8 @@ public:
BlockDerivative &getDerivative() { return _derivative; }
private:
BlockDerivative _derivative;
- BlockParam<float> _kP;
- BlockParam<float> _kD;
+ control::BlockParamFloat _kP;
+ control::BlockParamFloat _kD;
};
int __EXPORT blockPDTest();
@@ -372,9 +372,9 @@ private:
// attributes
BlockIntegral _integral;
BlockDerivative _derivative;
- BlockParam<float> _kP;
- BlockParam<float> _kI;
- BlockParam<float> _kD;
+ control::BlockParamFloat _kP;
+ control::BlockParamFloat _kI;
+ control::BlockParamFloat _kD;
};
int __EXPORT blockPIDTest();
@@ -404,7 +404,7 @@ public:
float get() { return _val; }
private:
// attributes
- BlockParam<float> _trim;
+ control::BlockParamFloat _trim;
BlockLimit _limit;
float _val;
};
@@ -439,8 +439,8 @@ public:
float getMax() { return _max.get(); }
private:
// attributes
- BlockParam<float> _min;
- BlockParam<float> _max;
+ control::BlockParamFloat _min;
+ control::BlockParamFloat _max;
};
int __EXPORT blockRandUniformTest();
@@ -486,8 +486,8 @@ public:
float getStdDev() { return _stdDev.get(); }
private:
// attributes
- BlockParam<float> _mean;
- BlockParam<float> _stdDev;
+ control::BlockParamFloat _mean;
+ control::BlockParamFloat _stdDev;
};
int __EXPORT blockRandGaussTest();