手动控制:
- 摇杆拨动,z:速度控制,yaw:速度控制,x,y:速度到角度控制
- 摇杆回中,位置和高度控制(包括爬升和速度控制)
自主控制:
- 航点,环绕,自动起飞、降落、归家
void
MulticopterPositionControl::do_control()
{
/* by default, run position/altitude controller. the control_* functions
* can disable this and run velocity controllers directly in this cycle */
_run_pos_control = true;
_run_alt_control = true;
if (_control_mode.flag_control_manual_enabled) {
/* manual control */
control_manual();
_mode_auto = false;
/* we set triplets to false
* this ensures that when switching to auto, the position
* controller will not use the old triplets but waits until triplets
* have been updated */
_pos_sp_triplet.current.valid = false;
_pos_sp_triplet.previous.valid = false;
_curr_pos_sp = matrix::Vector3f(NAN, NAN, NAN);
_hold_offboard_xy = false;
_hold_offboard_z = false;
} else {
/* reset acceleration to default */
_acceleration_state_dependent_xy = _acceleration_hor_max.get();
_acceleration_state_dependent_z = _acceleration_z_max_up.get();
control_non_manual();
}
}
void
MulticopterPositionControl::control_non_manual()
{
/* select control source */
if (_control_mode.flag_control_offboard_enabled) {
/* offboard control */
control_offboard();
_mode_auto = false;
} else {
_hold_offboard_xy = false;
_hold_offboard_z = false;
/* AUTO */
/* 产生期望位置 _pos_sp(0,1,2) */
control_auto();
}
// guard against any bad velocity values
bool velocity_valid = PX4_ISFINITE(_pos_sp_triplet.current.vx) &&
PX4_ISFINITE(_pos_sp_triplet.current.vy) &&
_pos_sp_triplet.current.velocity_valid;
/* 若期望速度小于目标速度,则适当增大期望速度,产生追赶目标的映像 */
// do not go slower than the follow target velocity when position tracking is active (set to valid)
if (_pos_sp_triplet.current.type == position_setpoint_s::SETPOINT_TYPE_FOLLOW_TARGET &&
velocity_valid &&
_pos_sp_triplet.current.position_valid) {
matrix::Vector3f ft_vel(_pos_sp_triplet.current.vx, _pos_sp_triplet.current.vy, 0.0f);
float cos_ratio = (ft_vel * _vel_sp) / (ft_vel.length() * _vel_sp.length());
// only override velocity set points when uav is traveling in same direction as target and vector component
// is greater than calculated position set point velocity component
if (cos_ratio > 0) {
ft_vel *= (cos_ratio);
// min speed a little faster than target vel
ft_vel += ft_vel.normalized() * 1.5f;
} else {
ft_vel.zero();
}
_vel_sp(0) = fabsf(ft_vel(0)) > fabsf(_vel_sp(0)) ? ft_vel(0) : _vel_sp(0);
_vel_sp(1) = fabsf(ft_vel(1)) > fabsf(_vel_sp(1)) ? ft_vel(1) : _vel_sp(1);
// track target using velocity only
} else if (_pos_sp_triplet.current.type == position_setpoint_s::SETPOINT_TYPE_FOLLOW_TARGET &&
velocity_valid) {
_vel_sp(0) = _pos_sp_triplet.current.vx;
_vel_sp(1) = _pos_sp_triplet.current.vy;
}
/* use constant descend rate when landing, ignore altitude setpoint */
if (_pos_sp_triplet.current.valid
&& _pos_sp_triplet.current.type == position_setpoint_s::SETPOINT_TYPE_LAND) {
_vel_sp(2) = _land_speed.get();
_run_alt_control = false;
}
if (_pos_sp_triplet.current.valid
&& _pos_sp_triplet.current.type == position_setpoint_s::SETPOINT_TYPE_IDLE) {
/* idle state, don't run controller and set zero thrust */
_R_setpoint.identity();
matrix::Quatf qd = _R_setpoint;
qd.copyTo(_att_sp.q_d);
_att_sp.q_d_valid = true;
_att_sp.roll_body = 0.0f;
_att_sp.pitch_body = 0.0f;
_att_sp.yaw_body = _yaw;
_att_sp.thrust = 0.0f;
_att_sp.timestamp = hrt_absolute_time();
} else {
control_position();
}
}
void
MulticopterPositionControl::control_position()
{
/* 外环P控制,根据期望位置,计算期望速度 */
calculate_velocity_setpoint();
if (_control_mode.flag_control_climb_rate_enabled || _control_mode.flag_control_velocity_enabled ||
_control_mode.flag_control_acceleration_enabled) {
/* 内环PID控制,根据期望速度,计算期望姿态 */
calculate_thrust_setpoint();
} else {
_reset_int_z = true;
}
}
vel_sp = pos_sp * P;
void
MulticopterPositionControl::calculate_velocity_setpoint()
{
/* run position & altitude controllers, if enabled (otherwise use already computed velocity setpoints) */
if (_run_pos_control) {
// If for any reason, we get a NaN position setpoint, we better just stay where we are.
if (PX4_ISFINITE(_pos_sp(0)) && PX4_ISFINITE(_pos_sp(1))) {
/* 外环位置P控制 */
_vel_sp(0) = (_pos_sp(0) - _pos(0)) * _pos_p(0);
_vel_sp(1) = (_pos_sp(1) - _pos(1)) * _pos_p(1);
} else {
_vel_sp(0) = 0.0f;
_vel_sp(1) = 0.0f;
warn_rate_limited("Caught invalid pos_sp in x and y");
}
}
/* 不在自动模式下,z速度进行一次限制 */
/* in auto the setpoint is already limited by the navigator */
if (!_control_mode.flag_control_auto_enabled) {
limit_altitude();
}
if (_run_alt_control) {
if (PX4_ISFINITE(_pos_sp(2))) {
/* 外环高度P控制 */
_vel_sp(2) = (_pos_sp(2) - _pos(2)) * _pos_p(2);
} else {
_vel_sp(2) = 0.0f;
warn_rate_limited("Caught invalid pos_sp in z");
}
}
if (!_control_mode.flag_control_position_enabled) {
_reset_pos_sp = true;
}
if (!_control_mode.flag_control_altitude_enabled) {
_reset_alt_sp = true;
}
if (!_control_mode.flag_control_velocity_enabled) {
_vel_sp_prev(0) = _vel(0);
_vel_sp_prev(1) = _vel(1);
_vel_sp(0) = 0.0f;
_vel_sp(1) = 0.0f;
}
if (!_control_mode.flag_control_climb_rate_enabled) {
_vel_sp(2) = 0.0f;
}
/* 自动起飞时,10m以下z速度逐步线性改变,如 0-5m-->1.5m/s
5-10m-->1.5m/s-3m/s
10m以上-->3m/s
-- */
/* limit vertical upwards speed in auto takeoff and close to ground */
float altitude_above_home = -_pos(2) + _home_pos.z;
if (_pos_sp_triplet.current.valid
&& _pos_sp_triplet.current.type == position_setpoint_s::SETPOINT_TYPE_TAKEOFF
&& !_control_mode.flag_control_manual_enabled) {
float vel_limit = math::gradual(altitude_above_home,
_slow_land_alt2.get(), _slow_land_alt1.get(),
_tko_speed.get(), _vel_max_up.get());
_vel_sp(2) = math::max(_vel_sp(2), -vel_limit);
}
/* encourage pilot to respect estimator height limitations when in manually controlled modes and not landing */
if (PX4_ISFINITE(_local_pos.hagl_min) // We need height limiting
&& _control_mode.flag_control_manual_enabled // Vehicle is under manual control
&& _control_mode.flag_control_altitude_enabled // Altitude controller is running
&& !manual_wants_landing()) { // Operator is not trying to land
if (_local_pos.dist_bottom < _local_pos.hagl_min) {
// If distance to ground is less than limit, increment setpoint upwards at up to the landing descent rate
float climb_rate_bias = fminf(1.5f * _pos_p(2) * (_local_pos.hagl_min - _local_pos.dist_bottom), _land_speed.get());
_vel_sp(2) -= climb_rate_bias;
_pos_sp(2) -= climb_rate_bias * _dt;
}
}
/* 降落时,10m以下z速度逐步线性改变,如 0-5m-->0.7m/s
5-10m-->0.7m/s-1m/s
10m以上-->1m/s
-- */
/* limit vertical downwards speed (positive z) close to ground
* for now we use the altitude above home and assume that we want to land at same height as we took off */
float vel_limit = math::gradual(altitude_above_home,
_slow_land_alt2.get(), _slow_land_alt1.get(),
_land_speed.get(), _vel_max_down.get());
/* 加速度限制,若期望加速度(根据当前期望速度与上次期望速度)过大,则根据加
速度最大参数进行限幅 ,包括,x,y,z轴*/
/* apply slewrate (aka acceleration limit) for smooth flying */
if (!_control_mode.flag_control_auto_enabled && !_in_smooth_takeoff) {
vel_sp_slewrate();
}
/* special velocity setpoint limitation for smooth takeoff (after slewrate!) */
if (_in_smooth_takeoff) {
set_takeoff_velocity(_vel_sp(2));
}
/* x,y轴速度进行限幅 */
/* make sure velocity setpoint is constrained in all directions (xyz) */
float vel_norm_xy = sqrtf(_vel_sp(0) * _vel_sp(0) + _vel_sp(1) * _vel_sp(1));
/* check if the velocity demand is significant */
_vel_sp_significant = vel_norm_xy > 0.5f * _vel_max_xy;
if (vel_norm_xy > _vel_max_xy) {
_vel_sp(0) = _vel_sp(0) * _vel_max_xy / vel_norm_xy;
_vel_sp(1) = _vel_sp(1) * _vel_max_xy / vel_norm_xy;
}
/* z轴速度进行限幅 */
_vel_sp(2) = math::constrain(_vel_sp(2), -_vel_max_up.get(), _vel_max_down.get());
_vel_sp_prev = _vel_sp;
}
thrust_sp = vel_err.emult(_vel_p) + _vel_err_d.emult(_vel_d)
+ _thrust_int - matrix::Vector3f(0.0f, 0.0f, _thr_hover.get())
由期望速度得到各轴推力分量,推力分量可得到期望姿态的DCM,进入可得
期望姿态。
void
MulticopterPositionControl::calculate_thrust_setpoint()
{
/* reset integrals if needed */
if (_control_mode.flag_control_climb_rate_enabled) {
if (_reset_int_z) {
_reset_int_z = false;
_thrust_int(2) = 0.0f;
}
} else {
_reset_int_z = true;
}
if (_control_mode.flag_control_velocity_enabled) {
if (_reset_int_xy) {
_reset_int_xy = false;
_thrust_int(0) = 0.0f;
_thrust_int(1) = 0.0f;
}
} else {
_reset_int_xy = true;
}
/* if any of the velocity setpoint is bogus, it's probably safest to command no velocity at all. */
for (int i = 0; i < 3; ++i) {
if (!PX4_ISFINITE(_vel_sp(i))) {
_vel_sp(i) = 0.0f;
}
}
/* 求速度偏差 */
/* velocity error */
matrix::Vector3f vel_err = _vel_sp - _vel;
/* thrust vector in NED frame */
matrix::Vector3f thrust_sp;
if (_control_mode.flag_control_acceleration_enabled && _pos_sp_triplet.current.acceleration_valid) {
thrust_sp = matrix::Vector3f(_pos_sp_triplet.current.a_x, _pos_sp_triplet.current.a_y, _pos_sp_triplet.current.a_z);
} else {
/* 内环速度PID,得各轴推力 */
thrust_sp = vel_err.emult(_vel_p) + _vel_err_d.emult(_vel_d)
+ _thrust_int - matrix::Vector3f(0.0f, 0.0f, _thr_hover.get());
}
if (!_control_mode.flag_control_velocity_enabled && !_control_mode.flag_control_acceleration_enabled) {
thrust_sp(0) = 0.0f;
thrust_sp(1) = 0.0f;
}
/* 第一次限制,落地前z推力限制,将推力向量转移到机体系下,x,y轴分量清零,z轴不动,再转
回导航系下。 */
// reduce thrust in early landing detection states to check if the vehicle still moves
landdetection_thrust_limit(thrust_sp);
if (!_control_mode.flag_control_climb_rate_enabled && !_control_mode.flag_control_acceleration_enabled) {
thrust_sp(2) = 0.0f;
}
/* limit thrust vector and check for saturation */
bool saturation_xy = false;
bool saturation_z = false;
/* limit min lift */
float thr_min = _thr_min.get();
if (!_control_mode.flag_control_velocity_enabled && thr_min < 0.0f) {
/* don't allow downside thrust direction in manual attitude mode */
thr_min = 0.0f;
}
float tilt_max = _tilt_max_air;
float thr_max = _thr_max.get();
// We can only run the control if we're already in-air, have a takeoff setpoint,
// or if we're in offboard control.
// Otherwise, we should just bail out
if (_vehicle_land_detected.landed && !in_auto_takeoff() && !manual_wants_takeoff()) {
// Keep throttle low while still on ground.
thr_max = 0.0f;
} else if (!_control_mode.flag_control_manual_enabled && _pos_sp_triplet.current.valid &&
_pos_sp_triplet.current.type == position_setpoint_s::SETPOINT_TYPE_LAND) {
/* adjust limits for landing mode */
/* limit max tilt and min lift when landing */
tilt_max = _tilt_max_land;
}
/* 第二次限制,z推力需要大于最小值0.12,z推力方向跟z轴方向一样,由天指地,从上到下范围(-1,0) */
/* limit min lift */
if (-thrust_sp(2) < thr_min) {
thrust_sp(2) = -thr_min;
/* Don't freeze altitude integral if it wants to throttle up */
/* 推力最小时,若还在加速,则积分饱和,反之允许积分 */
saturation_z = vel_err(2) > 0.0f ? true : saturation_z;
}
/* 第三次限制, 保证四旋翼的倾斜程度不超过最大倾斜角。
--为保证四旋翼不超过其最大倾斜角。保持竖直方向的升力不变,计算当前水平
方向推力是否超过水平方向可提供的最大推力,如果超过将其等比例缩小,使推
力的合力为最大推力值。 --*/
if (_control_mode.flag_control_velocity_enabled || _control_mode.flag_control_acceleration_enabled) {
/* limit max tilt */
if (thr_min >= 0.0f && tilt_max < M_PI_F / 2.0f - 0.05f) {
/* absolute horizontal thrust */
float thrust_sp_xy_len = matrix::Vector2f(thrust_sp(0), thrust_sp(1)).length();
if (thrust_sp_xy_len > 0.01f) {
/* max horizontal thrust for given vertical thrust*/
float thrust_xy_max = -thrust_sp(2) * tanf(tilt_max);
if (thrust_sp_xy_len > thrust_xy_max) {
float k = thrust_xy_max / thrust_sp_xy_len;
thrust_sp(0) *= k;
thrust_sp(1) *= k;
/* Don't freeze x,y integrals if they both want to throttle down */
saturation_xy = ((vel_err(0) * _vel_sp(0) < 0.0f) && (vel_err(1) * _vel_sp(1) < 0.0f)) ? saturation_xy : true;
}
}
}
}
/* 第四次限制,若位置上速度控制没有使能,高度上爬坡速度使能,则在z推力上给予补偿。 */
if (_control_mode.flag_control_climb_rate_enabled && !_control_mode.flag_control_velocity_enabled) {
/* thrust compensation when vertical velocity but not horizontal velocity is controlled */
float att_comp;
const float tilt_cos_max = 0.7f;
if (_R(2, 2) > tilt_cos_max) {
att_comp = 1.0f / _R(2, 2);
} else if (_R(2, 2) > 0.0f) {
att_comp = ((1.0f / tilt_cos_max - 1.0f) / tilt_cos_max) * _R(2, 2) + 1.0f;
saturation_z = true;
} else {
att_comp = 1.0f;
saturation_z = true;
}
thrust_sp(2) *= att_comp;
}
/* -- 第五次限制,总推力限幅
当总推力(转移到机体系下的z轴推力)大于最大值时进行限幅:
1、z轴(导航系下)推力向上并大于最大值,则x,y上的推力分量置零,z设为最大值;
2、z轴(导航系下)推力向上并小于最大值,则x,y上的推力分量等比例缩减,z不变;
3、z轴(导航下下)推力方向向下,则x,y,z都等比例缩减。
/* Calculate desired total thrust amount in body z direction. */
/* To compensate for excess thrust during attitude tracking errors we
* project the desired thrust force vector F onto the real vehicle's thrust axis in NED:
* body thrust axis [0,0,-1]' rotated by R is: R*[0,0,-1]' = -R_z */
matrix::Vector3f R_z(_R(0, 2), _R(1, 2), _R(2, 2));
/* 转移到机体系下的合推力值 */
/* recalculate because it might have changed */
float thrust_body_z = thrust_sp.dot(-R_z);
/* limit max thrust */
if (fabsf(thrust_body_z) > thr_max) {
if (thrust_sp(2) < 0.0f) {
if (-thrust_sp(2) > thr_max) {
/* thrust Z component is too large, limit it */
thrust_sp(0) = 0.0f;
thrust_sp(1) = 0.0f;
thrust_sp(2) = -thr_max;
saturation_xy = true;
/* Don't freeze altitude integral if it wants to throttle down */
saturation_z = vel_err(2) < 0.0f ? true : saturation_z;
} else {
/* preserve thrust Z component and lower XY, keeping altitude is more important than position */
float thrust_xy_max = sqrtf(thr_max * thr_max - thrust_sp(2) * thrust_sp(2));
float thrust_xy_abs = matrix::Vector2f(thrust_sp(0), thrust_sp(1)).length();
float k = thrust_xy_max / thrust_xy_abs;
thrust_sp(0) *= k;
thrust_sp(1) *= k;
/* Don't freeze x,y integrals if they both want to throttle down */
saturation_xy = ((vel_err(0) * _vel_sp(0) < 0.0f) && (vel_err(1) * _vel_sp(1) < 0.0f)) ? saturation_xy : true;
}
} else {
/* Z component is positive, going down (Z is positive down in NED), simply limit thrust vector */
float k = thr_max / fabsf(thrust_body_z);
thrust_sp *= k;
saturation_xy = true;
saturation_z = true;
}
thrust_body_z = thr_max;
}
/* if any of the thrust setpoint is bogus, send out a warning */
if (!PX4_ISFINITE(thrust_sp(0)) || !PX4_ISFINITE(thrust_sp(1)) || !PX4_ISFINITE(thrust_sp(2))) {
warn_rate_limited("Thrust setpoint not finite");
}
/* 合推力需发布出去,给姿态控制器 */
_att_sp.thrust = math::max(thrust_body_z, thr_min);
/* x,y,z误差积分 */
/* update integrals */
if (_control_mode.flag_control_velocity_enabled && !saturation_xy) {
_thrust_int(0) += vel_err(0) * _vel_i(0) * _dt;
_thrust_int(1) += vel_err(1) * _vel_i(1) * _dt;
}
if (_control_mode.flag_control_climb_rate_enabled && !saturation_z) {
_thrust_int(2) += vel_err(2) * _vel_i(2) * _dt;
}
/* 计算期望姿态角与四元数 */
/* calculate attitude setpoint from thrust vector */
if (_control_mode.flag_control_velocity_enabled || _control_mode.flag_control_acceleration_enabled) {
/* desired body_z axis = -normalize(thrust_vector) */
matrix::Vector3f body_x;
matrix::Vector3f body_y;
matrix::Vector3f body_z;
/* 推力向量单位化后取负,即为机体系的单位z轴,推力向量的合力是机体系的z负轴,需取反 */
if (thrust_sp.length() > SIGMA_NORM) {
body_z = -thrust_sp.normalized();
} else {
/* no thrust, set Z axis to safe value */
body_z = {0.0f, 0.0f, 1.0f};
}
/* vector of desired yaw direction in XY plane, rotated by PI/2 */
/* 机体系y轴在导航系xoy平面上的投影,由偏航角求得 */
matrix::Vector3f y_C(-sinf(_att_sp.yaw_body), cosf(_att_sp.yaw_body), 0.0f);
if (fabsf(body_z(2)) > SIGMA_SINGLE_OP) {
/* desired body_x axis, orthogonal to body_z */
/* 投影向量与机体系z向量叉乘,即为机体系x轴单位向量 */
body_x = y_C % body_z;
/* keep nose to front while inverted upside down */
if (body_z(2) < 0.0f) {
body_x = -body_x;
}
body_x.normalize();
} else {
/* desired thrust is in XY plane, set X downside to construct correct matrix,
* but yaw component will not be used actually */
body_x.zero();
body_x(2) = 1.0f;
}
/* 机体系z轴与机体系x轴叉乘,得到机体系z轴 */
/* desired body_y axis */
body_y = body_z % body_x;
/* 将机体系三轴分量组成期望姿态的方向余弦矩阵 */
/* fill rotation matrix */
for (int i = 0; i < 3; i++) {
_R_setpoint(i, 0) = body_x(i);
_R_setpoint(i, 1) = body_y(i);
_R_setpoint(i, 2) = body_z(i);
}
/* 方向余弦矩阵求得期望四元数,则可发布给姿态控制器 */
/* copy quaternion setpoint to attitude setpoint topic */
matrix::Quatf q_sp = _R_setpoint;
q_sp.copyTo(_att_sp.q_d);
_att_sp.q_d_valid = true;
/* calculate euler angles, for logging only, must not be used for control */
matrix::Eulerf euler = _R_setpoint;
_att_sp.roll_body = euler(0);
_att_sp.pitch_body = euler(1);
/* yaw already used to construct rot matrix, but actual rotation matrix can have different yaw near singularity */
} else if (!_control_mode.flag_control_manual_enabled) {
/* autonomous altitude control without position control (failsafe landing),
* force level attitude, don't change yaw */
_R_setpoint = matrix::Eulerf(0.0f, 0.0f, _att_sp.yaw_body);
/* copy quaternion setpoint to attitude setpoint topic */
matrix::Quatf q_sp = _R_setpoint;
q_sp.copyTo(_att_sp.q_d);
_att_sp.q_d_valid = true;
_att_sp.roll_body = 0.0f;
_att_sp.pitch_body = 0.0f;
}
/* save thrust setpoint for logging */
_local_pos_sp.acc_x = thrust_sp(0) * CONSTANTS_ONE_G;
_local_pos_sp.acc_y = thrust_sp(1) * CONSTANTS_ONE_G;
_local_pos_sp.acc_z = thrust_sp(2) * CONSTANTS_ONE_G;
_att_sp.timestamp = hrt_absolute_time();
}
期望位置——-》期望速度——–》期望推力,都在导航系;期望推力z与导航系z同向;
合推力为机体系z轴;
位置控制器预估一个当前期望位置,对当前期望位置进行多次修正,产生有效的期望位置。期望位置与位置估计模块产生的真实位置比较,得出位置误差,位置误差乘以位置比例系数得出粗略的期望速度。对粗略的期望速度进行几次修正得到有效的期望速度。期望速度与姿态估计模块产生的真实速度比较,得出速度误差,计算速度误差的导数,采用PID算法,将速度误差乘以比例系数,速度误差的导数乘以微分系数,将速度误差的积分乘以积分系数,三者求和即为粗略的推力矢量和。对粗略的推力矢量和进行多次修正和限制,得到有效的推力矢量和。由推力矢量和即可得出机体坐标系三轴的方向,将表示三轴方向的方向余弦矩阵转换为四元数表示。四元数表示的期望姿态由此产生,送至姿态控制器,经mixer与电机驱动输出推力,至此完成PX4开源飞控中位置控制的全部过程。