|
|
|
@ -55,7 +55,6 @@ using namespace std;
@@ -55,7 +55,6 @@ using namespace std;
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
MulticopterAttitudeControlBase::MulticopterAttitudeControlBase() : |
|
|
|
|
_v_att_sp_mod(), |
|
|
|
|
_v_rates_sp_mod(), |
|
|
|
|
_actuators(), |
|
|
|
|
_publish_att_sp(false) |
|
|
|
@ -67,9 +66,6 @@ MulticopterAttitudeControlBase::MulticopterAttitudeControlBase() :
@@ -67,9 +66,6 @@ MulticopterAttitudeControlBase::MulticopterAttitudeControlBase() :
|
|
|
|
|
_params.rate_d.zero(); |
|
|
|
|
_params.yaw_ff = 0.0f; |
|
|
|
|
_params.yaw_rate_max = 0.0f; |
|
|
|
|
_params.man_roll_max = 0.0f; |
|
|
|
|
_params.man_pitch_max = 0.0f; |
|
|
|
|
_params.man_yaw_max = 0.0f; |
|
|
|
|
_params.acro_rate_max.zero(); |
|
|
|
|
|
|
|
|
|
_rates_prev.zero(); |
|
|
|
@ -87,101 +83,11 @@ MulticopterAttitudeControlBase::~MulticopterAttitudeControlBase()
@@ -87,101 +83,11 @@ MulticopterAttitudeControlBase::~MulticopterAttitudeControlBase()
|
|
|
|
|
|
|
|
|
|
void MulticopterAttitudeControlBase::control_attitude(float dt) |
|
|
|
|
{ |
|
|
|
|
float yaw_sp_move_rate = 0.0f; |
|
|
|
|
_publish_att_sp = false; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (_v_control_mode->data().flag_control_manual_enabled) { |
|
|
|
|
/* manual input, set or modify attitude setpoint */ |
|
|
|
|
|
|
|
|
|
if (_v_control_mode->data().flag_control_velocity_enabled |
|
|
|
|
|| _v_control_mode->data().flag_control_climb_rate_enabled) { |
|
|
|
|
/* in assisted modes poll 'vehicle_attitude_setpoint' topic and modify it */ |
|
|
|
|
//XXX get rid of memcpy
|
|
|
|
|
memcpy(&(_v_att_sp_mod.data()), &_v_att_sp->data(), sizeof(_v_att_sp_mod.data())); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (!_v_control_mode->data().flag_control_climb_rate_enabled) { |
|
|
|
|
/* pass throttle directly if not in altitude stabilized mode */ |
|
|
|
|
_v_att_sp_mod.data().thrust = _manual_control_sp->data().z; |
|
|
|
|
_publish_att_sp = true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (!_armed->data().armed) { |
|
|
|
|
/* reset yaw setpoint when disarmed */ |
|
|
|
|
_reset_yaw_sp = true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* reset yaw setpoint to current position if needed */ |
|
|
|
|
if (_reset_yaw_sp) { |
|
|
|
|
_reset_yaw_sp = false; |
|
|
|
|
_v_att_sp_mod.data().yaw_body = _v_att->data().yaw; |
|
|
|
|
_v_att_sp_mod.data().R_valid = false; |
|
|
|
|
// _publish_att_sp = true;
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (!_v_control_mode->data().flag_control_velocity_enabled) { |
|
|
|
|
|
|
|
|
|
if (_v_att_sp_mod.data().thrust < 0.1f) { |
|
|
|
|
// TODO
|
|
|
|
|
//if (_status.condition_landed) {
|
|
|
|
|
/* reset yaw setpoint if on ground */ |
|
|
|
|
// reset_yaw_sp = true;
|
|
|
|
|
//}
|
|
|
|
|
} else { |
|
|
|
|
/* move yaw setpoint */ |
|
|
|
|
yaw_sp_move_rate = _manual_control_sp->data().r * _params.man_yaw_max; |
|
|
|
|
_v_att_sp_mod.data().yaw_body = _wrap_pi( |
|
|
|
|
_v_att_sp_mod.data().yaw_body + yaw_sp_move_rate * dt); |
|
|
|
|
float yaw_offs_max = _params.man_yaw_max / _params.att_p(2); |
|
|
|
|
float yaw_offs = _wrap_pi(_v_att_sp_mod.data().yaw_body - _v_att->data().yaw); |
|
|
|
|
|
|
|
|
|
if (yaw_offs < -yaw_offs_max) { |
|
|
|
|
_v_att_sp_mod.data().yaw_body = _wrap_pi(_v_att->data().yaw - yaw_offs_max); |
|
|
|
|
|
|
|
|
|
} else if (yaw_offs > yaw_offs_max) { |
|
|
|
|
_v_att_sp_mod.data().yaw_body = _wrap_pi(_v_att->data().yaw + yaw_offs_max); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
_v_att_sp_mod.data().R_valid = false; |
|
|
|
|
// _publish_att_sp = true;
|
|
|
|
|
} |
|
|
|
|
/* update attitude setpoint if not in position control mode */ |
|
|
|
|
_v_att_sp_mod.data().roll_body = _manual_control_sp->data().y * _params.man_roll_max; |
|
|
|
|
_v_att_sp_mod.data().pitch_body = -_manual_control_sp->data().x |
|
|
|
|
* _params.man_pitch_max; |
|
|
|
|
_v_att_sp_mod.data().R_valid = false; |
|
|
|
|
// _publish_att_sp = true;
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
/* in non-manual mode use 'vehicle_attitude_setpoint' topic */ |
|
|
|
|
//XXX get rid of memcpy
|
|
|
|
|
memcpy(&(_v_att_sp_mod.data()), &_v_att_sp->data(), sizeof(_v_att_sp_mod.data())); |
|
|
|
|
|
|
|
|
|
/* reset yaw setpoint after non-manual control mode */ |
|
|
|
|
_reset_yaw_sp = true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
_thrust_sp = _v_att_sp_mod.data().thrust; |
|
|
|
|
_thrust_sp = _v_att_sp->data().thrust; |
|
|
|
|
|
|
|
|
|
/* construct attitude setpoint rotation matrix */ |
|
|
|
|
math::Matrix<3, 3> R_sp; |
|
|
|
|
|
|
|
|
|
if (_v_att_sp_mod.data().R_valid) { |
|
|
|
|
/* rotation matrix in _att_sp is valid, use it */ |
|
|
|
|
R_sp.set(&_v_att_sp_mod.data().R_body[0]); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
/* rotation matrix in _att_sp is not valid, use euler angles instead */ |
|
|
|
|
R_sp.from_euler(_v_att_sp_mod.data().roll_body, _v_att_sp_mod.data().pitch_body, |
|
|
|
|
_v_att_sp_mod.data().yaw_body); |
|
|
|
|
|
|
|
|
|
/* copy rotation matrix back to setpoint struct */ |
|
|
|
|
memcpy(&_v_att_sp_mod.data().R_body[0], &R_sp.data[0][0], |
|
|
|
|
sizeof(_v_att_sp_mod.data().R_body)); |
|
|
|
|
_v_att_sp_mod.data().R_valid = true; |
|
|
|
|
} |
|
|
|
|
R_sp.set(_v_att_sp->data().R_body); |
|
|
|
|
|
|
|
|
|
/* rotation matrix for current state */ |
|
|
|
|
math::Matrix<3, 3> R; |
|
|
|
@ -190,11 +96,11 @@ void MulticopterAttitudeControlBase::control_attitude(float dt)
@@ -190,11 +96,11 @@ void MulticopterAttitudeControlBase::control_attitude(float dt)
|
|
|
|
|
/* all input data is ready, run controller itself */ |
|
|
|
|
|
|
|
|
|
/* try to move thrust vector shortest way, because yaw response is slower than roll/pitch */ |
|
|
|
|
math::Vector < 3 > R_z(R(0, 2), R(1, 2), R(2, 2)); |
|
|
|
|
math::Vector < 3 > R_sp_z(R_sp(0, 2), R_sp(1, 2), R_sp(2, 2)); |
|
|
|
|
math::Vector <3> R_z(R(0, 2), R(1, 2), R(2, 2)); |
|
|
|
|
math::Vector <3> R_sp_z(R_sp(0, 2), R_sp(1, 2), R_sp(2, 2)); |
|
|
|
|
|
|
|
|
|
/* axis and sin(angle) of desired rotation */ |
|
|
|
|
math::Vector < 3 > e_R = R.transposed() * (R_z % R_sp_z); |
|
|
|
|
math::Vector <3> e_R = R.transposed() * (R_z % R_sp_z); |
|
|
|
|
|
|
|
|
|
/* calculate angle error */ |
|
|
|
|
float e_R_z_sin = e_R.length(); |
|
|
|
@ -209,7 +115,7 @@ void MulticopterAttitudeControlBase::control_attitude(float dt)
@@ -209,7 +115,7 @@ void MulticopterAttitudeControlBase::control_attitude(float dt)
|
|
|
|
|
if (e_R_z_sin > 0.0f) { |
|
|
|
|
/* get axis-angle representation */ |
|
|
|
|
float e_R_z_angle = atan2f(e_R_z_sin, e_R_z_cos); |
|
|
|
|
math::Vector < 3 > e_R_z_axis = e_R / e_R_z_sin; |
|
|
|
|
math::Vector <3> e_R_z_axis = e_R / e_R_z_sin; |
|
|
|
|
|
|
|
|
|
e_R = e_R_z_axis * e_R_z_angle; |
|
|
|
|
|
|
|
|
@ -224,9 +130,7 @@ void MulticopterAttitudeControlBase::control_attitude(float dt)
@@ -224,9 +130,7 @@ void MulticopterAttitudeControlBase::control_attitude(float dt)
|
|
|
|
|
e_R_cp(2, 1) = e_R_z_axis(0); |
|
|
|
|
|
|
|
|
|
/* rotation matrix for roll/pitch only rotation */ |
|
|
|
|
R_rp = R |
|
|
|
|
* (_I + e_R_cp * e_R_z_sin |
|
|
|
|
+ e_R_cp * e_R_cp * (1.0f - e_R_z_cos)); |
|
|
|
|
R_rp = R * (_I + e_R_cp * e_R_z_sin + e_R_cp * e_R_cp * (1.0f - e_R_z_cos)); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
/* zero roll/pitch rotation */ |
|
|
|
@ -234,8 +138,8 @@ void MulticopterAttitudeControlBase::control_attitude(float dt)
@@ -234,8 +138,8 @@ void MulticopterAttitudeControlBase::control_attitude(float dt)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* R_rp and R_sp has the same Z axis, calculate yaw error */ |
|
|
|
|
math::Vector < 3 > R_sp_x(R_sp(0, 0), R_sp(1, 0), R_sp(2, 0)); |
|
|
|
|
math::Vector < 3 > R_rp_x(R_rp(0, 0), R_rp(1, 0), R_rp(2, 0)); |
|
|
|
|
math::Vector <3> R_sp_x(R_sp(0, 0), R_sp(1, 0), R_sp(2, 0)); |
|
|
|
|
math::Vector <3> R_rp_x(R_rp(0, 0), R_rp(1, 0), R_rp(2, 0)); |
|
|
|
|
e_R(2) = atan2f((R_rp_x % R_sp_x) * R_sp_z, R_rp_x * R_sp_x) * yaw_w; |
|
|
|
|
|
|
|
|
|
if (e_R_z_cos < 0.0f) { |
|
|
|
@ -243,7 +147,7 @@ void MulticopterAttitudeControlBase::control_attitude(float dt)
@@ -243,7 +147,7 @@ void MulticopterAttitudeControlBase::control_attitude(float dt)
|
|
|
|
|
* calculate angle and axis for R -> R_sp rotation directly */ |
|
|
|
|
math::Quaternion q; |
|
|
|
|
q.from_dcm(R.transposed() * R_sp); |
|
|
|
|
math::Vector < 3 > e_R_d = q.imag(); |
|
|
|
|
math::Vector <3> e_R_d = q.imag(); |
|
|
|
|
e_R_d.normalize(); |
|
|
|
|
e_R_d *= 2.0f * atan2f(e_R_d.length(), q(0)); |
|
|
|
|
|
|
|
|
@ -260,7 +164,8 @@ void MulticopterAttitudeControlBase::control_attitude(float dt)
@@ -260,7 +164,8 @@ void MulticopterAttitudeControlBase::control_attitude(float dt)
|
|
|
|
|
_params.yaw_rate_max); |
|
|
|
|
|
|
|
|
|
/* feed forward yaw setpoint rate */ |
|
|
|
|
_rates_sp(2) += yaw_sp_move_rate * yaw_w * _params.yaw_ff; |
|
|
|
|
_rates_sp(2) += _v_att_sp->data().yaw_sp_move_rate * yaw_w * _params.yaw_ff; |
|
|
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void MulticopterAttitudeControlBase::control_attitude_rates(float dt) |
|
|
|
|