aboutsummaryrefslogtreecommitdiff
path: root/src/lib
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-01-05 15:20:11 +0100
committerLorenz Meier <lm@inf.ethz.ch>2014-01-05 15:20:11 +0100
commitf00e14f749b371be485958bcb48e54da26c761e4 (patch)
tree4d0bbc119cbb2eb346b600d659db5a7db01968cc /src/lib
parent018e42733a568f5545864520866c891ed104d783 (diff)
parentf387c0ccc3fca38a2989b784847743b752a78de6 (diff)
downloadpx4-firmware-f00e14f749b371be485958bcb48e54da26c761e4.tar.gz
px4-firmware-f00e14f749b371be485958bcb48e54da26c761e4.tar.bz2
px4-firmware-f00e14f749b371be485958bcb48e54da26c761e4.zip
Merge branch 'navigator_new' of github.com:PX4/Firmware into navigator_new
Diffstat (limited to 'src/lib')
-rw-r--r--src/lib/launchdetection/LaunchDetector.cpp8
-rw-r--r--src/lib/launchdetection/LaunchDetector.h3
-rw-r--r--src/lib/launchdetection/launchdetection_params.c11
3 files changed, 16 insertions, 6 deletions
diff --git a/src/lib/launchdetection/LaunchDetector.cpp b/src/lib/launchdetection/LaunchDetector.cpp
index 2545e0a7e..67b32ad82 100644
--- a/src/lib/launchdetection/LaunchDetector.cpp
+++ b/src/lib/launchdetection/LaunchDetector.cpp
@@ -43,7 +43,8 @@
#include <systemlib/err.h>
LaunchDetector::LaunchDetector() :
- launchdetection_on(NULL, "LAUN_ALL_ON", false)
+ launchdetection_on(NULL, "LAUN_ALL_ON", false),
+ throttlePreTakeoff(NULL, "LAUN_THR_PRE", false)
{
/* init all detectors */
launchMethods[0] = new CatapultLaunchMethod();
@@ -83,10 +84,11 @@ bool LaunchDetector::getLaunchDetected()
void LaunchDetector::updateParams() {
warnx(" LaunchDetector::updateParams()");
- //launchdetection_on.update();
+ launchdetection_on.update();
+ throttlePreTakeoff.update();
for (uint8_t i = 0; i < sizeof(launchMethods)/sizeof(LaunchMethod); i++) {
- //launchMethods[i]->updateParams();
+ launchMethods[i]->updateParams();
warnx("updating component %d", i);
}
diff --git a/src/lib/launchdetection/LaunchDetector.h b/src/lib/launchdetection/LaunchDetector.h
index 981891143..7c2ff826c 100644
--- a/src/lib/launchdetection/LaunchDetector.h
+++ b/src/lib/launchdetection/LaunchDetector.h
@@ -59,11 +59,14 @@ public:
void updateParams();
bool launchDetectionEnabled() { return (bool)launchdetection_on.get(); };
+ float getThrottlePreTakeoff() {return throttlePreTakeoff.get(); }
+
// virtual bool getLaunchDetected();
protected:
private:
LaunchMethod* launchMethods[1];
control::BlockParamInt launchdetection_on;
+ control::BlockParamFloat throttlePreTakeoff;
};
diff --git a/src/lib/launchdetection/launchdetection_params.c b/src/lib/launchdetection/launchdetection_params.c
index 536749c88..63a8981aa 100644
--- a/src/lib/launchdetection/launchdetection_params.c
+++ b/src/lib/launchdetection/launchdetection_params.c
@@ -33,11 +33,11 @@
****************************************************************************/
/**
- * @file fw_pos_control_l1_params.c
+ * @file launchdetection_params.c
*
- * Parameters defined by the L1 position control task
+ * Parameters for launchdetection
*
- * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include <nuttx/config.h>
@@ -65,3 +65,8 @@ PARAM_DEFINE_FLOAT(LAUN_CAT_A, 30.0f);
// @Description LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection
// @Range > 0, in seconds
PARAM_DEFINE_FLOAT(LAUN_CAT_T, 0.05f);
+
+// @DisplayName Throttle setting while detecting the launch
+// @Description The throttle is set to this value while the system is waiting for the takeoff
+// @Range 0 to 1
+PARAM_DEFINE_FLOAT(LAUN_THR_PRE, 0.0f);