123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402 |
- #include "AC_AttitudeControl_Heli.h"
- #include <AP_HAL/AP_HAL.h>
- const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
-
- AP_NESTEDGROUPINFO(AC_AttitudeControl, 0),
-
-
-
-
-
-
- AP_GROUPINFO("HOVR_ROL_TRM", 1, AC_AttitudeControl_Heli, _hover_roll_trim, AC_ATTITUDE_HELI_HOVER_ROLL_TRIM_DEFAULT),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 2, AC_AttitudeControl_Heli, AC_HELI_PID),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 3, AC_AttitudeControl_Heli, AC_HELI_PID),
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 4, AC_AttitudeControl_Heli, AC_HELI_PID),
-
-
-
-
-
- AP_GROUPINFO("PIRO_COMP", 5, AC_AttitudeControl_Heli, _piro_comp_enabled, 0),
-
- AP_GROUPEND
- };
- void AC_AttitudeControl_Heli::passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds)
- {
-
- float yaw_rate_bf_rads = radians(yaw_rate_bf_cds * 0.01f);
-
-
- _passthrough_roll = roll_passthrough;
- _passthrough_pitch = pitch_passthrough;
- _passthrough_yaw = degrees(yaw_rate_bf_rads) * 100.0f;
-
- _flags_heli.flybar_passthrough = true;
-
- _attitude_target_ang_vel.x = _ahrs.get_gyro().x;
- _attitude_target_ang_vel.y = _ahrs.get_gyro().y;
-
- if (get_accel_yaw_max_radss() > 0.0f) {
- float rate_change_limit_rads = get_accel_yaw_max_radss() * _dt;
- float rate_change_rads = yaw_rate_bf_rads - _attitude_target_ang_vel.z;
- rate_change_rads = constrain_float(rate_change_rads, -rate_change_limit_rads, rate_change_limit_rads);
- _attitude_target_ang_vel.z += rate_change_rads;
- } else {
- _attitude_target_ang_vel.z = yaw_rate_bf_rads;
- }
- integrate_bf_rate_error_to_angle_errors();
- _att_error_rot_vec_rad.x = 0;
- _att_error_rot_vec_rad.y = 0;
-
- Vector3f att_error_euler_rad;
-
-
- if (ang_vel_to_euler_rate(Vector3f(_ahrs.roll, _ahrs.pitch, _ahrs.yaw), _att_error_rot_vec_rad, att_error_euler_rad)) {
- _attitude_target_euler_angle.x = wrap_PI(att_error_euler_rad.x + _ahrs.roll);
- _attitude_target_euler_angle.y = wrap_PI(att_error_euler_rad.y + _ahrs.pitch);
- _attitude_target_euler_angle.z = wrap_2PI(att_error_euler_rad.z + _ahrs.yaw);
- }
-
- if (_attitude_target_euler_angle.y > M_PI / 2.0f) {
- _attitude_target_euler_angle.x = wrap_PI(_attitude_target_euler_angle.x + M_PI);
- _attitude_target_euler_angle.y = wrap_PI(M_PI - _attitude_target_euler_angle.x);
- _attitude_target_euler_angle.z = wrap_2PI(_attitude_target_euler_angle.z + M_PI);
- }
- if (_attitude_target_euler_angle.y < -M_PI / 2.0f) {
- _attitude_target_euler_angle.x = wrap_PI(_attitude_target_euler_angle.x + M_PI);
- _attitude_target_euler_angle.y = wrap_PI(-M_PI - _attitude_target_euler_angle.x);
- _attitude_target_euler_angle.z = wrap_2PI(_attitude_target_euler_angle.z + M_PI);
- }
-
- _rate_target_ang_vel = update_ang_vel_target_from_att_error(_att_error_rot_vec_rad);
-
- _rate_target_ang_vel.x = _attitude_target_ang_vel.x;
- _rate_target_ang_vel.y = _attitude_target_ang_vel.y;
-
- _rate_target_ang_vel.z += _attitude_target_ang_vel.z;
- _thrust_error_angle = norm(_att_error_rot_vec_rad.x, _att_error_rot_vec_rad.y);
- }
- void AC_AttitudeControl_Heli::integrate_bf_rate_error_to_angle_errors()
- {
-
- _att_error_rot_vec_rad += (_attitude_target_ang_vel - _ahrs.get_gyro()) * _dt;
-
- _att_error_rot_vec_rad.x = constrain_float(_att_error_rot_vec_rad.x, -AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD, AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD);
- _att_error_rot_vec_rad.y = constrain_float(_att_error_rot_vec_rad.y, -AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD, AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD);
- _att_error_rot_vec_rad.z = constrain_float(_att_error_rot_vec_rad.z, -AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD, AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD);
- }
- void AC_AttitudeControl_Heli::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)
- {
- _passthrough_yaw = yaw_rate_bf_cds;
- AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(roll_rate_bf_cds, pitch_rate_bf_cds, yaw_rate_bf_cds);
- }
- void AC_AttitudeControl_Heli::rate_controller_run()
- {
- Vector3f gyro_latest = _ahrs.get_gyro_latest();
-
-
- if (_flags_heli.flybar_passthrough) {
- _motors.set_roll(_passthrough_roll / 4500.0f);
- _motors.set_pitch(_passthrough_pitch / 4500.0f);
- } else {
- rate_bf_to_motor_roll_pitch(gyro_latest, _rate_target_ang_vel.x, _rate_target_ang_vel.y);
- }
- if (_flags_heli.tail_passthrough) {
- _motors.set_yaw(_passthrough_yaw / 4500.0f);
- } else {
- _motors.set_yaw(rate_target_to_motor_yaw(gyro_latest.z, _rate_target_ang_vel.z));
- }
- }
- void AC_AttitudeControl_Heli::update_althold_lean_angle_max(float throttle_in)
- {
- float althold_lean_angle_max = acosf(constrain_float(_throttle_in / AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX, 0.0f, 1.0f));
- _althold_lean_angle_max = _althold_lean_angle_max + (_dt / (_dt + _angle_limit_tc)) * (althold_lean_angle_max - _althold_lean_angle_max);
- }
- void AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(const Vector3f &rate_rads, float rate_roll_target_rads, float rate_pitch_target_rads)
- {
- if (_flags_heli.leaky_i) {
- _pid_rate_roll.update_leaky_i(AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE);
- }
- float roll_pid = _pid_rate_roll.update_all(rate_roll_target_rads, rate_rads.x, _flags_heli.limit_roll);
- if (_flags_heli.leaky_i) {
- _pid_rate_pitch.update_leaky_i(AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE);
- }
- float pitch_pid = _pid_rate_pitch.update_all(rate_pitch_target_rads, rate_rads.y, _flags_heli.limit_pitch);
-
- float roll_ff = _pid_rate_roll.get_ff();
- float pitch_ff = _pid_rate_pitch.get_ff();
-
- float roll_out = roll_pid + roll_ff;
- float pitch_out = pitch_pid + pitch_ff;
-
- if (fabsf(roll_out) > AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX) {
- roll_out = constrain_float(roll_out, -AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX);
- _flags_heli.limit_roll = true;
- } else {
- _flags_heli.limit_roll = false;
- }
- if (fabsf(pitch_out) > AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX) {
- pitch_out = constrain_float(pitch_out, -AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX);
- _flags_heli.limit_pitch = true;
- } else {
- _flags_heli.limit_pitch = false;
- }
-
- _motors.set_roll(roll_out);
- _motors.set_pitch(pitch_out);
-
-
-
-
- if (_piro_comp_enabled) {
-
- const float piro_roll_i = _pid_rate_roll.get_i();
- const float piro_pitch_i = _pid_rate_pitch.get_i();
- Vector2f yawratevector;
- yawratevector.x = cosf(-rate_rads.z * _dt);
- yawratevector.y = sinf(-rate_rads.z * _dt);
- yawratevector.normalize();
- _pid_rate_roll.set_integrator(piro_roll_i * yawratevector.x - piro_pitch_i * yawratevector.y);
- _pid_rate_pitch.set_integrator(piro_pitch_i * yawratevector.x + piro_roll_i * yawratevector.y);
- }
- }
- float AC_AttitudeControl_Heli::rate_target_to_motor_yaw(float rate_yaw_actual_rads, float rate_target_rads)
- {
- if (!((AP_MotorsHeli&)_motors).rotor_runup_complete()) {
- _pid_rate_yaw.update_leaky_i(AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE);
- }
- float pid = _pid_rate_yaw.update_all(rate_target_rads, rate_yaw_actual_rads, _flags_heli.limit_yaw);
-
- float vff = _pid_rate_yaw.get_ff();
-
- float yaw_out = pid + vff;
-
- if (fabsf(yaw_out) > AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX) {
- yaw_out = constrain_float(yaw_out, -AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX);
- _flags_heli.limit_yaw = true;
- } else {
- _flags_heli.limit_yaw = false;
- }
-
- return yaw_out;
- }
- void AC_AttitudeControl_Heli::set_throttle_out(float throttle_in, bool apply_angle_boost, float filter_cutoff)
- {
- _throttle_in = throttle_in;
- update_althold_lean_angle_max(throttle_in);
- _motors.set_throttle_filter_cutoff(filter_cutoff);
- _motors.set_throttle(throttle_in);
-
- _angle_boost = 0.0f;
- }
- void AC_AttitudeControl_Heli::input_euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds)
- {
- if (_inverted_flight) {
- euler_roll_angle_cd = wrap_180_cd(euler_roll_angle_cd + 18000);
- }
- AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, euler_yaw_rate_cds);
- }
- void AC_AttitudeControl_Heli::input_euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw)
- {
- if (_inverted_flight) {
- euler_roll_angle_cd = wrap_180_cd(euler_roll_angle_cd + 18000);
- }
- AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, euler_yaw_angle_cd, slew_yaw);
- }
|