forked from Archive/PX4-Autopilot
FlightTaskManualAltitude: Rename _min_speed_down -> _max_speed_down as it is the maximum allowed downward speed
This commit is contained in:
parent
c0d1aa1654
commit
c80593a144
|
@ -64,7 +64,7 @@ bool FlightTaskManualAltitude::activate(vehicle_local_position_setpoint_s last_s
|
||||||
_updateConstraintsFromEstimator();
|
_updateConstraintsFromEstimator();
|
||||||
|
|
||||||
_max_speed_up = _constraints.speed_up;
|
_max_speed_up = _constraints.speed_up;
|
||||||
_min_speed_down = _constraints.speed_down;
|
_max_speed_down = _constraints.speed_down;
|
||||||
|
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
@ -246,7 +246,7 @@ void FlightTaskManualAltitude::_respectMaxAltitude()
|
||||||
// below the maximum, preserving control loop vertical position error gain.
|
// below the maximum, preserving control loop vertical position error gain.
|
||||||
if (PX4_ISFINITE(_constraints.max_distance_to_ground)) {
|
if (PX4_ISFINITE(_constraints.max_distance_to_ground)) {
|
||||||
_constraints.speed_up = math::constrain(_param_mpc_z_p.get() * (_constraints.max_distance_to_ground - _dist_to_bottom),
|
_constraints.speed_up = math::constrain(_param_mpc_z_p.get() * (_constraints.max_distance_to_ground - _dist_to_bottom),
|
||||||
-_min_speed_down, _max_speed_up);
|
-_max_speed_down, _max_speed_up);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
_constraints.speed_up = _max_speed_up;
|
_constraints.speed_up = _max_speed_up;
|
||||||
|
@ -259,10 +259,10 @@ void FlightTaskManualAltitude::_respectMaxAltitude()
|
||||||
// set position setpoint to maximum distance to ground
|
// set position setpoint to maximum distance to ground
|
||||||
_position_setpoint(2) = _position(2) + delta_distance_to_max;
|
_position_setpoint(2) = _position(2) + delta_distance_to_max;
|
||||||
// limit speed downwards to 0.7m/s
|
// limit speed downwards to 0.7m/s
|
||||||
_constraints.speed_down = math::min(_min_speed_down, 0.7f);
|
_constraints.speed_down = math::min(_max_speed_down, 0.7f);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
_constraints.speed_down = _min_speed_down;
|
_constraints.speed_down = _max_speed_down;
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -126,7 +126,7 @@ private:
|
||||||
float _yawspeed_filter_state{}; /**< state of low-pass filter in rad/s */
|
float _yawspeed_filter_state{}; /**< state of low-pass filter in rad/s */
|
||||||
uint8_t _reset_counter = 0; /**< counter for estimator resets in z-direction */
|
uint8_t _reset_counter = 0; /**< counter for estimator resets in z-direction */
|
||||||
float _max_speed_up = 10.0f;
|
float _max_speed_up = 10.0f;
|
||||||
float _min_speed_down = 1.0f;
|
float _max_speed_down = 1.0f;
|
||||||
bool _terrain_follow{false}; /**< true when the vehicle is following the terrain height */
|
bool _terrain_follow{false}; /**< true when the vehicle is following the terrain height */
|
||||||
bool _terrain_hold{false}; /**< true when vehicle is controlling height above a static ground position */
|
bool _terrain_hold{false}; /**< true when vehicle is controlling height above a static ground position */
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue