mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-07 17:35:22 +08:00
Merge branch 'master' of github.com:PX4/Firmware into st24
This commit is contained in:
@@ -238,7 +238,7 @@ void TECS::_update_height_demand(float demand, float state)
|
||||
_hgt_dem_adj = demand;//0.025f * demand + 0.975f * _hgt_dem_adj_last;
|
||||
_hgt_dem_adj_last = _hgt_dem_adj;
|
||||
|
||||
_hgt_rate_dem = (_hgt_dem_adj-state)*_heightrate_p;
|
||||
_hgt_rate_dem = (_hgt_dem_adj-state)*_heightrate_p + _heightrate_ff * (_hgt_dem_adj - _hgt_dem_adj_last)/_DT;
|
||||
// Limit height rate of change
|
||||
if (_hgt_rate_dem > _maxClimbRate) {
|
||||
_hgt_rate_dem = _maxClimbRate;
|
||||
|
||||
@@ -47,6 +47,7 @@ public:
|
||||
_rollComp(0.0f),
|
||||
_spdWeight(0.5f),
|
||||
_heightrate_p(0.0f),
|
||||
_heightrate_ff(0.0f),
|
||||
_speedrate_p(0.0f),
|
||||
_throttle_dem(0.0f),
|
||||
_pitch_dem(0.0f),
|
||||
@@ -220,6 +221,10 @@ public:
|
||||
_heightrate_p = heightrate_p;
|
||||
}
|
||||
|
||||
void set_heightrate_ff(float heightrate_ff) {
|
||||
_heightrate_ff = heightrate_ff;
|
||||
}
|
||||
|
||||
void set_speedrate_p(float speedrate_p) {
|
||||
_speedrate_p = speedrate_p;
|
||||
}
|
||||
@@ -256,6 +261,7 @@ private:
|
||||
float _rollComp;
|
||||
float _spdWeight;
|
||||
float _heightrate_p;
|
||||
float _heightrate_ff;
|
||||
float _speedrate_p;
|
||||
|
||||
// throttle demand in the range from 0.0 to 1.0
|
||||
|
||||
@@ -49,9 +49,11 @@ CatapultLaunchMethod::CatapultLaunchMethod(SuperBlock *parent) :
|
||||
SuperBlock(parent, "CAT"),
|
||||
last_timestamp(hrt_absolute_time()),
|
||||
integrator(0.0f),
|
||||
launchDetected(false),
|
||||
threshold_accel(this, "A"),
|
||||
threshold_time(this, "T")
|
||||
state(LAUNCHDETECTION_RES_NONE),
|
||||
thresholdAccel(this, "A"),
|
||||
thresholdTime(this, "T"),
|
||||
motorDelay(this, "MDEL"),
|
||||
pitchMaxPreThrottle(this, "PMAX")
|
||||
{
|
||||
|
||||
}
|
||||
@@ -65,34 +67,66 @@ void CatapultLaunchMethod::update(float accel_x)
|
||||
float dt = (float)hrt_elapsed_time(&last_timestamp) * 1e-6f;
|
||||
last_timestamp = hrt_absolute_time();
|
||||
|
||||
if (accel_x > threshold_accel.get()) {
|
||||
integrator += dt;
|
||||
// warnx("*** integrator %.3f, threshold_accel %.3f, threshold_time %.3f, accel_x %.3f, dt %.3f",
|
||||
// (double)integrator, (double)threshold_accel.get(), (double)threshold_time.get(), (double)accel_x, (double)dt);
|
||||
if (integrator > threshold_time.get()) {
|
||||
launchDetected = true;
|
||||
switch (state) {
|
||||
case LAUNCHDETECTION_RES_NONE:
|
||||
/* Detect a acceleration that is longer and stronger as the minimum given by the params */
|
||||
if (accel_x > thresholdAccel.get()) {
|
||||
integrator += dt;
|
||||
if (integrator > thresholdTime.get()) {
|
||||
if (motorDelay.get() > 0.0f) {
|
||||
state = LAUNCHDETECTION_RES_DETECTED_ENABLECONTROL;
|
||||
warnx("Launch detected: state: enablecontrol, waiting %.2fs until using full"
|
||||
" throttle", (double)motorDelay.get());
|
||||
} else {
|
||||
/* No motor delay set: go directly to enablemotors state */
|
||||
state = LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS;
|
||||
warnx("Launch detected: state: enablemotors (delay not activated)");
|
||||
}
|
||||
}
|
||||
} else {
|
||||
/* reset */
|
||||
reset();
|
||||
}
|
||||
break;
|
||||
|
||||
case LAUNCHDETECTION_RES_DETECTED_ENABLECONTROL:
|
||||
/* Vehicle is currently controlling attitude but not with full throttle. Waiting undtil delay is
|
||||
* over to allow full throttle */
|
||||
motorDelayCounter += dt;
|
||||
if (motorDelayCounter > motorDelay.get()) {
|
||||
warnx("Launch detected: state enablemotors");
|
||||
state = LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
|
||||
} else {
|
||||
// warnx("integrator %.3f, threshold_accel %.3f, threshold_time %.3f, accel_x %.3f, dt %.3f",
|
||||
// (double)integrator, (double)threshold_accel.get(), (double)threshold_time.get(), (double)accel_x, (double)dt);
|
||||
/* reset integrator */
|
||||
integrator = 0.0f;
|
||||
launchDetected = false;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
bool CatapultLaunchMethod::getLaunchDetected()
|
||||
LaunchDetectionResult CatapultLaunchMethod::getLaunchDetected() const
|
||||
{
|
||||
return launchDetected;
|
||||
return state;
|
||||
}
|
||||
|
||||
|
||||
void CatapultLaunchMethod::reset()
|
||||
{
|
||||
integrator = 0.0f;
|
||||
launchDetected = false;
|
||||
motorDelayCounter = 0.0f;
|
||||
state = LAUNCHDETECTION_RES_NONE;
|
||||
}
|
||||
|
||||
float CatapultLaunchMethod::getPitchMax(float pitchMaxDefault) {
|
||||
/* If motor is turned on do not impose the extra limit on maximum pitch */
|
||||
if (state == LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS) {
|
||||
return pitchMaxDefault;
|
||||
} else {
|
||||
return pitchMaxPreThrottle.get();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@@ -57,16 +57,23 @@ public:
|
||||
~CatapultLaunchMethod();
|
||||
|
||||
void update(float accel_x);
|
||||
bool getLaunchDetected();
|
||||
LaunchDetectionResult getLaunchDetected() const;
|
||||
void reset();
|
||||
float getPitchMax(float pitchMaxDefault);
|
||||
|
||||
private:
|
||||
hrt_abstime last_timestamp;
|
||||
float integrator;
|
||||
bool launchDetected;
|
||||
float motorDelayCounter;
|
||||
|
||||
control::BlockParamFloat threshold_accel;
|
||||
control::BlockParamFloat threshold_time;
|
||||
LaunchDetectionResult state;
|
||||
|
||||
control::BlockParamFloat thresholdAccel;
|
||||
control::BlockParamFloat thresholdTime;
|
||||
control::BlockParamFloat motorDelay;
|
||||
control::BlockParamFloat pitchMaxPreThrottle; /**< Upper pitch limit before throttle is turned on.
|
||||
Can be used to make sure that the AC does not climb
|
||||
too much while attached to a bungee */
|
||||
|
||||
};
|
||||
|
||||
|
||||
@@ -46,6 +46,7 @@ namespace launchdetection
|
||||
|
||||
LaunchDetector::LaunchDetector() :
|
||||
SuperBlock(NULL, "LAUN"),
|
||||
activeLaunchDetectionMethodIndex(-1),
|
||||
launchdetection_on(this, "ALL_ON"),
|
||||
throttlePreTakeoff(this, "THR_PRE")
|
||||
{
|
||||
@@ -65,7 +66,14 @@ LaunchDetector::~LaunchDetector()
|
||||
void LaunchDetector::reset()
|
||||
{
|
||||
/* Reset all detectors */
|
||||
launchMethods[0]->reset();
|
||||
for (uint8_t i = 0; i < sizeof(launchMethods)/sizeof(LaunchMethod); i++) {
|
||||
launchMethods[i]->reset();
|
||||
}
|
||||
|
||||
/* Reset active launchdetector */
|
||||
activeLaunchDetectionMethodIndex = -1;
|
||||
|
||||
|
||||
}
|
||||
|
||||
void LaunchDetector::update(float accel_x)
|
||||
@@ -77,17 +85,44 @@ void LaunchDetector::update(float accel_x)
|
||||
}
|
||||
}
|
||||
|
||||
bool LaunchDetector::getLaunchDetected()
|
||||
LaunchDetectionResult LaunchDetector::getLaunchDetected()
|
||||
{
|
||||
if (launchdetection_on.get() == 1) {
|
||||
for (uint8_t i = 0; i < sizeof(launchMethods)/sizeof(LaunchMethod); i++) {
|
||||
if(launchMethods[i]->getLaunchDetected()) {
|
||||
return true;
|
||||
if (activeLaunchDetectionMethodIndex < 0) {
|
||||
/* None of the active launchmethods has detected a launch, check all launchmethods */
|
||||
for (uint8_t i = 0; i < sizeof(launchMethods)/sizeof(LaunchMethod); i++) {
|
||||
if(launchMethods[i]->getLaunchDetected() != LAUNCHDETECTION_RES_NONE) {
|
||||
warnx("selecting launchmethod %d", i);
|
||||
activeLaunchDetectionMethodIndex = i; // from now on only check this method
|
||||
return launchMethods[i]->getLaunchDetected();
|
||||
}
|
||||
}
|
||||
} else {
|
||||
return launchMethods[activeLaunchDetectionMethodIndex]->getLaunchDetected();
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
return LAUNCHDETECTION_RES_NONE;
|
||||
}
|
||||
|
||||
float LaunchDetector::getPitchMax(float pitchMaxDefault) {
|
||||
if (!launchdetection_on.get()) {
|
||||
return pitchMaxDefault;
|
||||
}
|
||||
|
||||
/* if a lauchdetectionmethod is active or only one exists return the pitch limit from this method,
|
||||
* otherwise use the default limit */
|
||||
if (activeLaunchDetectionMethodIndex < 0) {
|
||||
if (sizeof(launchMethods)/sizeof(LaunchMethod) > 1) {
|
||||
return pitchMaxDefault;
|
||||
} else {
|
||||
return launchMethods[0]->getPitchMax(pitchMaxDefault);
|
||||
}
|
||||
} else {
|
||||
return launchMethods[activeLaunchDetectionMethodIndex]->getPitchMax(pitchMaxDefault);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
@@ -59,14 +59,23 @@ public:
|
||||
void reset();
|
||||
|
||||
void update(float accel_x);
|
||||
bool getLaunchDetected();
|
||||
LaunchDetectionResult getLaunchDetected();
|
||||
bool launchDetectionEnabled() { return (bool)launchdetection_on.get(); };
|
||||
|
||||
float getThrottlePreTakeoff() {return throttlePreTakeoff.get(); }
|
||||
|
||||
/* Returns a maximum pitch in deg. Different launch methods may impose upper pitch limits during launch */
|
||||
float getPitchMax(float pitchMaxDefault);
|
||||
|
||||
// virtual bool getLaunchDetected();
|
||||
protected:
|
||||
private:
|
||||
int activeLaunchDetectionMethodIndex; /**< holds a index to the launchMethod in the array launchMethods
|
||||
which detected a Launch. If no launchMethod has detected a launch yet the
|
||||
value is -1. Once one launchMetthod has detected a launch only this
|
||||
method is checked for further adavancing in the state machine (e.g. when
|
||||
to power up the motors) */
|
||||
|
||||
LaunchMethod* launchMethods[1];
|
||||
control::BlockParamInt launchdetection_on;
|
||||
control::BlockParamFloat throttlePreTakeoff;
|
||||
|
||||
@@ -44,13 +44,27 @@
|
||||
namespace launchdetection
|
||||
{
|
||||
|
||||
enum LaunchDetectionResult {
|
||||
LAUNCHDETECTION_RES_NONE = 0, /**< No launch has been detected */
|
||||
LAUNCHDETECTION_RES_DETECTED_ENABLECONTROL = 1, /**< Launch has been detected, the controller should
|
||||
control the attitude. However any motors should not throttle
|
||||
up and still be set to 'throttlePreTakeoff'.
|
||||
For instance this is used to have a delay for the motor
|
||||
when launching a fixed wing aircraft from a bungee */
|
||||
LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS = 2 /**< Launch has been detected, teh controller should control
|
||||
attitude and also throttle up the motors. */
|
||||
};
|
||||
|
||||
class LaunchMethod
|
||||
{
|
||||
public:
|
||||
virtual void update(float accel_x) = 0;
|
||||
virtual bool getLaunchDetected() = 0;
|
||||
virtual LaunchDetectionResult getLaunchDetected() const = 0;
|
||||
virtual void reset() = 0;
|
||||
|
||||
/* Returns a upper pitch limit if required, otherwise returns pitchMaxDefault */
|
||||
virtual float getPitchMax(float pitchMaxDefault) = 0;
|
||||
|
||||
protected:
|
||||
private:
|
||||
};
|
||||
|
||||
@@ -77,6 +77,31 @@ PARAM_DEFINE_FLOAT(LAUN_CAT_A, 30.0f);
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(LAUN_CAT_T, 0.05f);
|
||||
|
||||
/**
|
||||
* Motor delay
|
||||
*
|
||||
* Delay between starting attitude control and powering up the throttle (giving throttle control to the controller)
|
||||
* Before this timespan is up the throttle will be set to LAUN_THR_PRE, set to 0 to deactivate
|
||||
*
|
||||
* @unit seconds
|
||||
* @min 0
|
||||
* @group Launch detection
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(LAUN_CAT_MDEL, 0.0f);
|
||||
|
||||
/**
|
||||
* Maximum pitch before the throttle is powered up (during motor delay phase)
|
||||
*
|
||||
* This is an extra limit for the maximum pitch which is imposed in the phase before the throttle turns on.
|
||||
* This allows to limit the maximum pitch angle during a bungee launch (make the launch less steep).
|
||||
*
|
||||
* @unit deg
|
||||
* @min 0
|
||||
* @max 45
|
||||
* @group Launch detection
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(LAUN_CAT_PMAX, 30.0f);
|
||||
|
||||
/**
|
||||
* Throttle setting while detecting launch.
|
||||
*
|
||||
|
||||
Reference in New Issue
Block a user