|
|
|
@ -85,13 +85,22 @@ bool FlightTaskManualAltitude::activate(vehicle_local_position_setpoint_s last_s
@@ -85,13 +85,22 @@ bool FlightTaskManualAltitude::activate(vehicle_local_position_setpoint_s last_s
|
|
|
|
|
|
|
|
|
|
void FlightTaskManualAltitude::_scaleSticks() |
|
|
|
|
{ |
|
|
|
|
// Use sticks input with deadzone and exponential curve for vertical velocity and yawspeed
|
|
|
|
|
_yawspeed_setpoint = _sticks_expo(3) * math::radians(_param_mpc_man_y_max.get()); |
|
|
|
|
// Use stick input with deadzone, exponential curve and first order lpf for yawspeed
|
|
|
|
|
const float yawspeed_target = _sticks_expo(3) * math::radians(_param_mpc_man_y_max.get()); |
|
|
|
|
_yawspeed_setpoint = _applyYawspeedFilter(yawspeed_target); |
|
|
|
|
|
|
|
|
|
// Use sticks input with deadzone and exponential curve for vertical velocity
|
|
|
|
|
const float vel_max_z = (_sticks(2) > 0.0f) ? _constraints.speed_down : _constraints.speed_up; |
|
|
|
|
_velocity_setpoint(2) = vel_max_z * _sticks_expo(2); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
float FlightTaskManualAltitude::_applyYawspeedFilter(float yawspeed_target) |
|
|
|
|
{ |
|
|
|
|
const float den = math::max(_param_mpc_man_y_tau.get() + _deltatime, 0.001f); |
|
|
|
|
const float alpha = _deltatime / den; |
|
|
|
|
return (1.f - alpha) * _yawspeed_setpoint + alpha * yawspeed_target; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void FlightTaskManualAltitude::_updateAltitudeLock() |
|
|
|
|
{ |
|
|
|
|
// Depending on stick inputs and velocity, position is locked.
|
|
|
|
@ -289,18 +298,36 @@ void FlightTaskManualAltitude::_rotateIntoHeadingFrame(Vector2f &v)
@@ -289,18 +298,36 @@ void FlightTaskManualAltitude::_rotateIntoHeadingFrame(Vector2f &v)
|
|
|
|
|
|
|
|
|
|
void FlightTaskManualAltitude::_updateHeadingSetpoints() |
|
|
|
|
{ |
|
|
|
|
/* Yaw-lock depends on stick input. If not locked,
|
|
|
|
|
* yaw_sp is set to NAN. |
|
|
|
|
* TODO: add yawspeed to get threshold.*/ |
|
|
|
|
if (fabsf(_yawspeed_setpoint) > FLT_EPSILON) { |
|
|
|
|
// no fixed heading when rotating around yaw by stick
|
|
|
|
|
_yaw_setpoint = NAN; |
|
|
|
|
if (_isYawInput()) { |
|
|
|
|
_unlockYaw(); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
// hold the current heading when no more rotation commanded
|
|
|
|
|
if (!PX4_ISFINITE(_yaw_setpoint)) { |
|
|
|
|
_yaw_setpoint = _yaw; |
|
|
|
|
} |
|
|
|
|
_lockYaw(); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
bool FlightTaskManualAltitude::_isYawInput() |
|
|
|
|
{ |
|
|
|
|
/*
|
|
|
|
|
* A threshold larger than FLT_EPSILON is required because the |
|
|
|
|
* _yawspeed_setpoint comes from an IIR filter and takes too much |
|
|
|
|
* time to reach zero. |
|
|
|
|
*/ |
|
|
|
|
return fabsf(_yawspeed_setpoint) > 0.001f; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void FlightTaskManualAltitude::_unlockYaw() |
|
|
|
|
{ |
|
|
|
|
// no fixed heading when rotating around yaw by stick
|
|
|
|
|
_yaw_setpoint = NAN; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void FlightTaskManualAltitude::_lockYaw() |
|
|
|
|
{ |
|
|
|
|
// hold the current heading when no more rotation commanded
|
|
|
|
|
if (!PX4_ISFINITE(_yaw_setpoint)) { |
|
|
|
|
_yaw_setpoint = _yaw; |
|
|
|
|
_yawspeed_setpoint = 0.f; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|