forked from Archive/PX4-Autopilot
Merge pull request #714 from thomasgubler/launchdetection_cleanup
launchdetection: better integration of Block class
This commit is contained in:
commit
100ad89079
|
@ -41,12 +41,16 @@
|
||||||
#include "CatapultLaunchMethod.h"
|
#include "CatapultLaunchMethod.h"
|
||||||
#include <systemlib/err.h>
|
#include <systemlib/err.h>
|
||||||
|
|
||||||
CatapultLaunchMethod::CatapultLaunchMethod() :
|
namespace launchdetection
|
||||||
|
{
|
||||||
|
|
||||||
|
CatapultLaunchMethod::CatapultLaunchMethod(SuperBlock *parent) :
|
||||||
|
SuperBlock(parent, "CAT"),
|
||||||
last_timestamp(hrt_absolute_time()),
|
last_timestamp(hrt_absolute_time()),
|
||||||
integrator(0.0f),
|
integrator(0.0f),
|
||||||
launchDetected(false),
|
launchDetected(false),
|
||||||
threshold_accel(NULL, "LAUN_CAT_A", false),
|
threshold_accel(this, "A"),
|
||||||
threshold_time(NULL, "LAUN_CAT_T", false)
|
threshold_time(this, "T")
|
||||||
{
|
{
|
||||||
|
|
||||||
}
|
}
|
||||||
|
@ -83,14 +87,11 @@ bool CatapultLaunchMethod::getLaunchDetected()
|
||||||
return launchDetected;
|
return launchDetected;
|
||||||
}
|
}
|
||||||
|
|
||||||
void CatapultLaunchMethod::updateParams()
|
|
||||||
{
|
|
||||||
threshold_accel.update();
|
|
||||||
threshold_time.update();
|
|
||||||
}
|
|
||||||
|
|
||||||
void CatapultLaunchMethod::reset()
|
void CatapultLaunchMethod::reset()
|
||||||
{
|
{
|
||||||
integrator = 0.0f;
|
integrator = 0.0f;
|
||||||
launchDetected = false;
|
launchDetected = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
|
@ -44,17 +44,20 @@
|
||||||
#include "LaunchMethod.h"
|
#include "LaunchMethod.h"
|
||||||
|
|
||||||
#include <drivers/drv_hrt.h>
|
#include <drivers/drv_hrt.h>
|
||||||
|
#include <controllib/blocks.hpp>
|
||||||
#include <controllib/block/BlockParam.hpp>
|
#include <controllib/block/BlockParam.hpp>
|
||||||
|
|
||||||
class CatapultLaunchMethod : public LaunchMethod
|
namespace launchdetection
|
||||||
|
{
|
||||||
|
|
||||||
|
class CatapultLaunchMethod : public LaunchMethod, public control::SuperBlock
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
CatapultLaunchMethod();
|
CatapultLaunchMethod(SuperBlock *parent);
|
||||||
~CatapultLaunchMethod();
|
~CatapultLaunchMethod();
|
||||||
|
|
||||||
void update(float accel_x);
|
void update(float accel_x);
|
||||||
bool getLaunchDetected();
|
bool getLaunchDetected();
|
||||||
void updateParams();
|
|
||||||
void reset();
|
void reset();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
@ -68,3 +71,5 @@ private:
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* CATAPULTLAUNCHMETHOD_H_ */
|
#endif /* CATAPULTLAUNCHMETHOD_H_ */
|
||||||
|
|
||||||
|
}
|
||||||
|
|
|
@ -42,12 +42,16 @@
|
||||||
#include "CatapultLaunchMethod.h"
|
#include "CatapultLaunchMethod.h"
|
||||||
#include <systemlib/err.h>
|
#include <systemlib/err.h>
|
||||||
|
|
||||||
|
namespace launchdetection
|
||||||
|
{
|
||||||
|
|
||||||
LaunchDetector::LaunchDetector() :
|
LaunchDetector::LaunchDetector() :
|
||||||
launchdetection_on(NULL, "LAUN_ALL_ON", false),
|
SuperBlock(NULL, "LAUN"),
|
||||||
throttlePreTakeoff(NULL, "LAUN_THR_PRE", false)
|
launchdetection_on(this, "ALL_ON"),
|
||||||
|
throttlePreTakeoff(this, "THR_PRE")
|
||||||
{
|
{
|
||||||
/* init all detectors */
|
/* init all detectors */
|
||||||
launchMethods[0] = new CatapultLaunchMethod();
|
launchMethods[0] = new CatapultLaunchMethod(this);
|
||||||
|
|
||||||
|
|
||||||
/* update all parameters of all detectors */
|
/* update all parameters of all detectors */
|
||||||
|
@ -87,12 +91,4 @@ bool LaunchDetector::getLaunchDetected()
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void LaunchDetector::updateParams() {
|
|
||||||
|
|
||||||
launchdetection_on.update();
|
|
||||||
throttlePreTakeoff.update();
|
|
||||||
|
|
||||||
for (uint8_t i = 0; i < sizeof(launchMethods)/sizeof(LaunchMethod); i++) {
|
|
||||||
launchMethods[i]->updateParams();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -45,10 +45,13 @@
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
#include "LaunchMethod.h"
|
#include "LaunchMethod.h"
|
||||||
|
#include <controllib/blocks.hpp>
|
||||||
#include <controllib/block/BlockParam.hpp>
|
#include <controllib/block/BlockParam.hpp>
|
||||||
|
|
||||||
class __EXPORT LaunchDetector
|
namespace launchdetection
|
||||||
|
{
|
||||||
|
|
||||||
|
class __EXPORT LaunchDetector : public control::SuperBlock
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
LaunchDetector();
|
LaunchDetector();
|
||||||
|
@ -57,7 +60,6 @@ public:
|
||||||
|
|
||||||
void update(float accel_x);
|
void update(float accel_x);
|
||||||
bool getLaunchDetected();
|
bool getLaunchDetected();
|
||||||
void updateParams();
|
|
||||||
bool launchDetectionEnabled() { return (bool)launchdetection_on.get(); };
|
bool launchDetectionEnabled() { return (bool)launchdetection_on.get(); };
|
||||||
|
|
||||||
float getThrottlePreTakeoff() {return throttlePreTakeoff.get(); }
|
float getThrottlePreTakeoff() {return throttlePreTakeoff.get(); }
|
||||||
|
@ -72,5 +74,6 @@ private:
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
#endif // LAUNCHDETECTOR_H
|
#endif // LAUNCHDETECTOR_H
|
||||||
|
|
|
@ -41,15 +41,20 @@
|
||||||
#ifndef LAUNCHMETHOD_H_
|
#ifndef LAUNCHMETHOD_H_
|
||||||
#define LAUNCHMETHOD_H_
|
#define LAUNCHMETHOD_H_
|
||||||
|
|
||||||
|
namespace launchdetection
|
||||||
|
{
|
||||||
|
|
||||||
class LaunchMethod
|
class LaunchMethod
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
virtual void update(float accel_x) = 0;
|
virtual void update(float accel_x) = 0;
|
||||||
virtual bool getLaunchDetected() = 0;
|
virtual bool getLaunchDetected() = 0;
|
||||||
virtual void updateParams() = 0;
|
|
||||||
virtual void reset() = 0;
|
virtual void reset() = 0;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
private:
|
private:
|
||||||
};
|
};
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
#endif /* LAUNCHMETHOD_H_ */
|
#endif /* LAUNCHMETHOD_H_ */
|
||||||
|
|
|
@ -186,7 +186,7 @@ private:
|
||||||
float target_bearing;
|
float target_bearing;
|
||||||
|
|
||||||
/* Launch detection */
|
/* Launch detection */
|
||||||
LaunchDetector launchDetector;
|
launchdetection::LaunchDetector launchDetector;
|
||||||
|
|
||||||
/* throttle and airspeed states */
|
/* throttle and airspeed states */
|
||||||
float _airspeed_error; ///< airspeed error to setpoint in m/s
|
float _airspeed_error; ///< airspeed error to setpoint in m/s
|
||||||
|
@ -989,6 +989,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||||
} else {
|
} else {
|
||||||
/* no takeoff detection --> fly */
|
/* no takeoff detection --> fly */
|
||||||
launch_detected = true;
|
launch_detected = true;
|
||||||
|
warnx("launchdetection off");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue