mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 20:28:37 +08:00
FlightTasks: do not adjust tilt limit of the position control
Adjusting the tilt limit can lead to diverging position control and should only be used by setting a sanity limit for the controller and not to adjust during the descent phase of a Land or RTL. Otherwise it leads to flyaways in important failsafe modes when there's stronger disturbance e.g. wind.
This commit is contained in:
committed by
Lorenz Meier
parent
95779ea670
commit
809b45eac8
@@ -127,14 +127,10 @@ void FlightTaskAutoMapper::_prepareIdleSetpoints()
|
|||||||
|
|
||||||
void FlightTaskAutoMapper::_prepareLandSetpoints()
|
void FlightTaskAutoMapper::_prepareLandSetpoints()
|
||||||
{
|
{
|
||||||
float land_speed = _getLandSpeed();
|
|
||||||
|
|
||||||
// Keep xy-position and go down with landspeed
|
// Keep xy-position and go down with landspeed
|
||||||
|
float land_speed = _getLandSpeed();
|
||||||
_position_setpoint = Vector3f(_target(0), _target(1), NAN);
|
_position_setpoint = Vector3f(_target(0), _target(1), NAN);
|
||||||
_velocity_setpoint = Vector3f(Vector3f(NAN, NAN, land_speed));
|
_velocity_setpoint = Vector3f(Vector3f(NAN, NAN, land_speed));
|
||||||
|
|
||||||
// set constraints
|
|
||||||
_constraints.tilt = math::radians(_param_mpc_tiltmax_lnd.get());
|
|
||||||
_gear.landing_gear = landing_gear_s::GEAR_DOWN;
|
_gear.landing_gear = landing_gear_s::GEAR_DOWN;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -181,7 +181,7 @@ void FlightTask::_setDefaultConstraints()
|
|||||||
_constraints.speed_xy = _param_mpc_xy_vel_max.get();
|
_constraints.speed_xy = _param_mpc_xy_vel_max.get();
|
||||||
_constraints.speed_up = _param_mpc_z_vel_max_up.get();
|
_constraints.speed_up = _param_mpc_z_vel_max_up.get();
|
||||||
_constraints.speed_down = _param_mpc_z_vel_max_dn.get();
|
_constraints.speed_down = _param_mpc_z_vel_max_dn.get();
|
||||||
_constraints.tilt = math::radians(_param_mpc_tiltmax_air.get());
|
_constraints.tilt = NAN;
|
||||||
_constraints.min_distance_to_ground = NAN;
|
_constraints.min_distance_to_ground = NAN;
|
||||||
_constraints.max_distance_to_ground = NAN;
|
_constraints.max_distance_to_ground = NAN;
|
||||||
_constraints.want_takeoff = false;
|
_constraints.want_takeoff = false;
|
||||||
|
|||||||
@@ -260,7 +260,6 @@ protected:
|
|||||||
DEFINE_PARAMETERS_CUSTOM_PARENT(ModuleParams,
|
DEFINE_PARAMETERS_CUSTOM_PARENT(ModuleParams,
|
||||||
(ParamFloat<px4::params::MPC_XY_VEL_MAX>) _param_mpc_xy_vel_max,
|
(ParamFloat<px4::params::MPC_XY_VEL_MAX>) _param_mpc_xy_vel_max,
|
||||||
(ParamFloat<px4::params::MPC_Z_VEL_MAX_DN>) _param_mpc_z_vel_max_dn,
|
(ParamFloat<px4::params::MPC_Z_VEL_MAX_DN>) _param_mpc_z_vel_max_dn,
|
||||||
(ParamFloat<px4::params::MPC_Z_VEL_MAX_UP>) _param_mpc_z_vel_max_up,
|
(ParamFloat<px4::params::MPC_Z_VEL_MAX_UP>) _param_mpc_z_vel_max_up
|
||||||
(ParamFloat<px4::params::MPC_TILTMAX_AIR>) _param_mpc_tiltmax_air
|
|
||||||
)
|
)
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -60,8 +60,6 @@ bool FlightTaskManualAltitude::activate(vehicle_local_position_setpoint_s last_s
|
|||||||
_velocity_setpoint(2) = 0.f;
|
_velocity_setpoint(2) = 0.f;
|
||||||
_setDefaultConstraints();
|
_setDefaultConstraints();
|
||||||
|
|
||||||
_constraints.tilt = math::radians(_param_mpc_man_tilt_max.get());
|
|
||||||
|
|
||||||
_updateConstraintsFromEstimator();
|
_updateConstraintsFromEstimator();
|
||||||
|
|
||||||
_max_speed_up = _constraints.speed_up;
|
_max_speed_up = _constraints.speed_up;
|
||||||
|
|||||||
@@ -61,8 +61,6 @@ bool FlightTaskManualPosition::activate(vehicle_local_position_setpoint_s last_s
|
|||||||
// all requirements from altitude-mode still have to hold
|
// all requirements from altitude-mode still have to hold
|
||||||
bool ret = FlightTaskManualAltitude::activate(last_setpoint);
|
bool ret = FlightTaskManualAltitude::activate(last_setpoint);
|
||||||
|
|
||||||
_constraints.tilt = math::radians(_param_mpc_tiltmax_air.get());
|
|
||||||
|
|
||||||
// set task specific constraint
|
// set task specific constraint
|
||||||
if (_constraints.speed_xy >= _param_mpc_vel_manual.get()) {
|
if (_constraints.speed_xy >= _param_mpc_vel_manual.get()) {
|
||||||
_constraints.speed_xy = _param_mpc_vel_manual.get();
|
_constraints.speed_xy = _param_mpc_vel_manual.get();
|
||||||
|
|||||||
@@ -109,7 +109,7 @@ public:
|
|||||||
|
|
||||||
/**
|
/**
|
||||||
* Set the maximum tilt angle in radians the output attitude is allowed to have
|
* Set the maximum tilt angle in radians the output attitude is allowed to have
|
||||||
* @param tilt angle from level orientation in radians
|
* @param tilt angle in radians from level orientation
|
||||||
*/
|
*/
|
||||||
void setTiltLimit(const float tilt) { _lim_tilt = tilt; }
|
void setTiltLimit(const float tilt) { _lim_tilt = tilt; }
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user