Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp
Views: 1798
#include "AC_AttitudeControl_Heli.h"1#include <AP_HAL/AP_HAL.h>2#include <AP_Scheduler/AP_Scheduler.h>34// table of user settable parameters5const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {6// parameters from parent vehicle7AP_NESTEDGROUPINFO(AC_AttitudeControl, 0),89// @Param: HOVR_ROL_TRM10// @DisplayName: Hover Roll Trim11// @Description: Trim the hover roll angle to counter tail rotor thrust in a hover12// @Units: cdeg13// @Increment: 1014// @Range: 0 100015// @User: Advanced16AP_GROUPINFO("HOVR_ROL_TRM", 1, AC_AttitudeControl_Heli, _hover_roll_trim, AC_ATTITUDE_HELI_HOVER_ROLL_TRIM_DEFAULT),1718// @Param: RAT_RLL_P19// @DisplayName: Roll axis rate controller P gain20// @Description: Roll axis rate controller P gain. Corrects in proportion to the difference between the desired roll rate vs actual roll rate21// @Range: 0.0 0.3522// @Increment: 0.00523// @User: Standard2425// @Param: RAT_RLL_I26// @DisplayName: Roll axis rate controller I gain27// @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate28// @Range: 0.0 0.629// @Increment: 0.0130// @User: Standard3132// @Param: RAT_RLL_IMAX33// @DisplayName: Roll axis rate controller I gain maximum34// @Description: Roll axis rate controller I gain maximum. Constrains the maximum that the I term will output35// @Range: 0 136// @Increment: 0.0137// @User: Standard3839// @Param: RAT_RLL_ILMI40// @DisplayName: Roll axis rate controller I-term leak minimum41// @Description: Point below which I-term will not leak down42// @Range: 0 143// @User: Advanced4445// @Param: RAT_RLL_D46// @DisplayName: Roll axis rate controller D gain47// @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate48// @Range: 0.0 0.0349// @Increment: 0.00150// @User: Standard5152// @Param: RAT_RLL_FF53// @DisplayName: Roll axis rate controller feed forward54// @Description: Roll axis rate controller feed forward55// @Range: 0.05 0.556// @Increment: 0.00157// @User: Standard5859// @Param: RAT_RLL_FLTT60// @DisplayName: Roll axis rate controller target frequency in Hz61// @Description: Roll axis rate controller target frequency in Hz62// @Range: 5 5063// @Increment: 164// @Units: Hz65// @User: Standard6667// @Param: RAT_RLL_FLTE68// @DisplayName: Roll axis rate controller error frequency in Hz69// @Description: Roll axis rate controller error frequency in Hz70// @Range: 5 5071// @Increment: 172// @Units: Hz73// @User: Standard7475// @Param: RAT_RLL_FLTD76// @DisplayName: Roll axis rate controller derivative frequency in Hz77// @Description: Roll axis rate controller derivative frequency in Hz78// @Range: 0 5079// @Increment: 180// @Units: Hz81// @User: Standard8283// @Param: RAT_RLL_SMAX84// @DisplayName: Roll slew rate limit85// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.86// @Range: 0 20087// @Increment: 0.588// @User: Advanced8990// @Param: RAT_RLL_D_FF91// @DisplayName: Roll Derivative FeedForward Gain92// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target93// @Range: 0 0.0294// @Increment: 0.000195// @User: Advanced9697// @Param: RAT_RLL_NTF98// @DisplayName: Roll Target notch filter index99// @Description: Roll Target notch filter index100// @Range: 1 8101// @User: Advanced102103// @Param: RAT_RLL_NEF104// @DisplayName: Roll Error notch filter index105// @Description: Roll Error notch filter index106// @Range: 1 8107// @User: Advanced108109AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 2, AC_AttitudeControl_Heli, AC_HELI_PID),110111// @Param: RAT_PIT_P112// @DisplayName: Pitch axis rate controller P gain113// @Description: Pitch axis rate controller P gain. Corrects in proportion to the difference between the desired pitch rate vs actual pitch rate114// @Range: 0.0 0.35115// @Increment: 0.005116// @User: Standard117118// @Param: RAT_PIT_I119// @DisplayName: Pitch axis rate controller I gain120// @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate121// @Range: 0.0 0.6122// @Increment: 0.01123// @User: Standard124125// @Param: RAT_PIT_IMAX126// @DisplayName: Pitch axis rate controller I gain maximum127// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum that the I term will output128// @Range: 0 1129// @Increment: 0.01130// @User: Standard131132// @Param: RAT_PIT_ILMI133// @DisplayName: Pitch axis rate controller I-term leak minimum134// @Description: Point below which I-term will not leak down135// @Range: 0 1136// @User: Advanced137138// @Param: RAT_PIT_D139// @DisplayName: Pitch axis rate controller D gain140// @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate141// @Range: 0.0 0.03142// @Increment: 0.001143// @User: Standard144145// @Param: RAT_PIT_FF146// @DisplayName: Pitch axis rate controller feed forward147// @Description: Pitch axis rate controller feed forward148// @Range: 0.05 0.5149// @Increment: 0.001150// @User: Standard151152// @Param: RAT_PIT_FLTT153// @DisplayName: Pitch axis rate controller target frequency in Hz154// @Description: Pitch axis rate controller target frequency in Hz155// @Range: 5 50156// @Increment: 1157// @Units: Hz158// @User: Standard159160// @Param: RAT_PIT_FLTE161// @DisplayName: Pitch axis rate controller error frequency in Hz162// @Description: Pitch axis rate controller error frequency in Hz163// @Range: 5 50164// @Increment: 1165// @Units: Hz166// @User: Standard167168// @Param: RAT_PIT_FLTD169// @DisplayName: Pitch axis rate controller derivative frequency in Hz170// @Description: Pitch axis rate controller derivative frequency in Hz171// @Range: 0 50172// @Increment: 1173// @Units: Hz174// @User: Standard175176// @Param: RAT_PIT_SMAX177// @DisplayName: Pitch slew rate limit178// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.179// @Range: 0 200180// @Increment: 0.5181// @User: Advanced182183// @Param: RAT_PIT_D_FF184// @DisplayName: Pitch Derivative FeedForward Gain185// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target186// @Range: 0 0.02187// @Increment: 0.0001188// @User: Advanced189190// @Param: RAT_PIT_NTF191// @DisplayName: Pitch Target notch filter index192// @Description: Pitch Target notch filter index193// @Range: 1 8194// @User: Advanced195196// @Param: RAT_PIT_NEF197// @DisplayName: Pitch Error notch filter index198// @Description: Pitch Error notch filter index199// @Range: 1 8200// @User: Advanced201202AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 3, AC_AttitudeControl_Heli, AC_HELI_PID),203204// @Param: RAT_YAW_P205// @DisplayName: Yaw axis rate controller P gain206// @Description: Yaw axis rate controller P gain. Corrects in proportion to the difference between the desired yaw rate vs actual yaw rate207// @Range: 0.180 0.60208// @Increment: 0.005209// @User: Standard210211// @Param: RAT_YAW_I212// @DisplayName: Yaw axis rate controller I gain213// @Description: Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate214// @Range: 0.01 0.2215// @Increment: 0.01216// @User: Standard217218// @Param: RAT_YAW_IMAX219// @DisplayName: Yaw axis rate controller I gain maximum220// @Description: Yaw axis rate controller I gain maximum. Constrains the maximum that the I term will output221// @Range: 0 1222// @Increment: 0.01223// @User: Standard224225// @Param: RAT_YAW_ILMI226// @DisplayName: Yaw axis rate controller I-term leak minimum227// @Description: Point below which I-term will not leak down228// @Range: 0 1229// @User: Advanced230231// @Param: RAT_YAW_D232// @DisplayName: Yaw axis rate controller D gain233// @Description: Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate234// @Range: 0.000 0.02235// @Increment: 0.001236// @User: Standard237238// @Param: RAT_YAW_FF239// @DisplayName: Yaw axis rate controller feed forward240// @Description: Yaw axis rate controller feed forward241// @Range: 0 0.5242// @Increment: 0.001243// @User: Standard244245// @Param: RAT_YAW_FLTT246// @DisplayName: Yaw axis rate controller target frequency in Hz247// @Description: Yaw axis rate controller target frequency in Hz248// @Range: 5 50249// @Increment: 1250// @Units: Hz251// @User: Standard252253// @Param: RAT_YAW_FLTE254// @DisplayName: Yaw axis rate controller error frequency in Hz255// @Description: Yaw axis rate controller error frequency in Hz256// @Range: 5 50257// @Increment: 1258// @Units: Hz259// @User: Standard260261// @Param: RAT_YAW_FLTD262// @DisplayName: Yaw axis rate controller derivative frequency in Hz263// @Description: Yaw axis rate controller derivative frequency in Hz264// @Range: 0 50265// @Increment: 1266// @Units: Hz267// @User: Standard268269// @Param: RAT_YAW_SMAX270// @DisplayName: Yaw slew rate limit271// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.272// @Range: 0 200273// @Increment: 0.5274// @User: Advanced275276// @Param: RAT_YAW_D_FF277// @DisplayName: Yaw Derivative FeedForward Gain278// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target279// @Range: 0 0.02280// @Increment: 0.0001281// @User: Advanced282283// @Param: RAT_YAW_NTF284// @DisplayName: Yaw Target notch filter index285// @Description: Yaw Target notch filter index286// @Range: 1 8287// @Units: Hz288// @User: Advanced289290// @Param: RAT_YAW_NEF291// @DisplayName: Yaw Error notch filter index292// @Description: Yaw Error notch filter index293// @Range: 1 8294// @User: Advanced295296AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 4, AC_AttitudeControl_Heli, AC_HELI_PID),297298// @Param: PIRO_COMP299// @DisplayName: Piro Comp Enable300// @Description: Pirouette compensation enabled301// @Values: 0:Disabled,1:Enabled302// @User: Advanced303AP_GROUPINFO("PIRO_COMP", 5, AC_AttitudeControl_Heli, _piro_comp_enabled, 0),304305AP_GROUPEND306};307308AC_AttitudeControl_Heli::AC_AttitudeControl_Heli(AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, AP_MotorsHeli& motors) :309AC_AttitudeControl(ahrs, aparm, motors)310{311AP_Param::setup_object_defaults(this, var_info);312313// initialise flags314_flags_heli.leaky_i = true;315_flags_heli.flybar_passthrough = false;316_flags_heli.tail_passthrough = false;317#if AP_FILTER_ENABLED318set_notch_sample_rate(AP::scheduler().get_loop_rate_hz());319#endif320}321322// passthrough_bf_roll_pitch_rate_yaw - passthrough the pilots roll and pitch inputs directly to swashplate for flybar acro mode323void AC_AttitudeControl_Heli::passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds)324{325// convert from centidegrees on public interface to radians326float yaw_rate_bf_rads = radians(yaw_rate_bf_cds * 0.01f);327328// store roll, pitch and passthroughs329// NOTE: this abuses yaw_rate_bf_rads330_passthrough_roll = roll_passthrough;331_passthrough_pitch = pitch_passthrough;332_passthrough_yaw = degrees(yaw_rate_bf_rads) * 100.0f;333334// set rate controller to use pass through335_flags_heli.flybar_passthrough = true;336337// set bf rate targets to current body frame rates (i.e. relax and be ready for vehicle to switch out of acro)338_ang_vel_target.x = _ahrs.get_gyro().x;339_ang_vel_target.y = _ahrs.get_gyro().y;340341// accel limit desired yaw rate342if (get_accel_yaw_max_radss() > 0.0f) {343float rate_change_limit_rads = get_accel_yaw_max_radss() * _dt;344float rate_change_rads = yaw_rate_bf_rads - _ang_vel_target.z;345rate_change_rads = constrain_float(rate_change_rads, -rate_change_limit_rads, rate_change_limit_rads);346_ang_vel_target.z += rate_change_rads;347} else {348_ang_vel_target.z = yaw_rate_bf_rads;349}350351integrate_bf_rate_error_to_angle_errors();352_att_error_rot_vec_rad.x = 0;353_att_error_rot_vec_rad.y = 0;354355// update our earth-frame angle targets356Vector3f att_error_euler_rad;357358// convert angle error rotation vector into 321-intrinsic euler angle difference359// NOTE: this results an an approximation linearized about the vehicle's attitude360Quaternion att;361_ahrs.get_quat_body_to_ned(att);362if (ang_vel_to_euler_rate(att, _att_error_rot_vec_rad, att_error_euler_rad)) {363_euler_angle_target.x = wrap_PI(att_error_euler_rad.x + _ahrs.roll);364_euler_angle_target.y = wrap_PI(att_error_euler_rad.y + _ahrs.pitch);365_euler_angle_target.z = wrap_2PI(att_error_euler_rad.z + _ahrs.yaw);366}367368// handle flipping over pitch axis369if (_euler_angle_target.y > M_PI / 2.0f) {370_euler_angle_target.x = wrap_PI(_euler_angle_target.x + M_PI);371_euler_angle_target.y = wrap_PI(M_PI - _euler_angle_target.x);372_euler_angle_target.z = wrap_2PI(_euler_angle_target.z + M_PI);373}374if (_euler_angle_target.y < -M_PI / 2.0f) {375_euler_angle_target.x = wrap_PI(_euler_angle_target.x + M_PI);376_euler_angle_target.y = wrap_PI(-M_PI - _euler_angle_target.x);377_euler_angle_target.z = wrap_2PI(_euler_angle_target.z + M_PI);378}379380// convert body-frame angle errors to body-frame rate targets381_ang_vel_body = update_ang_vel_target_from_att_error(_att_error_rot_vec_rad);382383// set body-frame roll/pitch rate target to current desired rates which are the vehicle's actual rates384_ang_vel_body.x = _ang_vel_target.x;385_ang_vel_body.y = _ang_vel_target.y;386387// add desired target to yaw388_ang_vel_body.z += _ang_vel_target.z;389_thrust_error_angle = _att_error_rot_vec_rad.xy().length();390}391392void AC_AttitudeControl_Heli::integrate_bf_rate_error_to_angle_errors()393{394// Integrate the angular velocity error into the attitude error395_att_error_rot_vec_rad += (_ang_vel_target - _ahrs.get_gyro()) * _dt;396397// Constrain attitude error398_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);399_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);400_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);401}402403// subclass non-passthrough too, for external gyro, no flybar404void AC_AttitudeControl_Heli::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)405{406_passthrough_yaw = yaw_rate_bf_cds;407408AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(roll_rate_bf_cds, pitch_rate_bf_cds, yaw_rate_bf_cds);409}410411//412// rate controller (body-frame) methods413//414415// rate_controller_run - run lowest level rate controller and send outputs to the motors416// should be called at 100hz or more417void AC_AttitudeControl_Heli::rate_controller_run()418{419_ang_vel_body += _sysid_ang_vel_body;420421_rate_gyro = _ahrs.get_gyro_latest();422_rate_gyro_time_us = AP_HAL::micros64();423424// call rate controllers and send output to motors object425// if using a flybar passthrough roll and pitch directly to motors426if (_flags_heli.flybar_passthrough) {427_motors.set_roll(_passthrough_roll / 4500.0f);428_motors.set_pitch(_passthrough_pitch / 4500.0f);429} else {430rate_bf_to_motor_roll_pitch(_rate_gyro, _ang_vel_body.x, _ang_vel_body.y);431}432if (_flags_heli.tail_passthrough) {433_motors.set_yaw(_passthrough_yaw / 4500.0f);434} else {435_motors.set_yaw(rate_target_to_motor_yaw(_rate_gyro.z, _ang_vel_body.z));436}437438_sysid_ang_vel_body.zero();439_actuator_sysid.zero();440441}442443// Update Alt_Hold angle maximum444void AC_AttitudeControl_Heli::update_althold_lean_angle_max(float throttle_in)445{446float althold_lean_angle_max = acosf(constrain_float(throttle_in / AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX, 0.0f, 1.0f));447_althold_lean_angle_max = _althold_lean_angle_max + (_dt / (_dt + _angle_limit_tc)) * (althold_lean_angle_max - _althold_lean_angle_max);448}449450//451// private methods452//453454//455// body-frame rate controller456//457458// rate_bf_to_motor_roll_pitch - ask the rate controller to calculate the motor outputs to achieve the target rate in radians/second459void AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(const Vector3f &rate_rads, float rate_roll_target_rads, float rate_pitch_target_rads)460{461462if (_flags_heli.leaky_i) {463_pid_rate_roll.update_leaky_i(AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE);464}465float roll_pid = _pid_rate_roll.update_all(rate_roll_target_rads, rate_rads.x, _dt, _motors.limit.roll) + _actuator_sysid.x;466467if (_flags_heli.leaky_i) {468_pid_rate_pitch.update_leaky_i(AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE);469}470471float pitch_pid = _pid_rate_pitch.update_all(rate_pitch_target_rads, rate_rads.y, _dt, _motors.limit.pitch) + _actuator_sysid.y;472473// use pid library to calculate ff474float roll_ff = _pid_rate_roll.get_ff();475float pitch_ff = _pid_rate_pitch.get_ff();476477// add feed forward and final output478float roll_out = roll_pid + roll_ff;479float pitch_out = pitch_pid + pitch_ff;480481// constrain output482roll_out = constrain_float(roll_out, -AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX);483pitch_out = constrain_float(pitch_out, -AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX);484485// output to motors486_motors.set_roll(roll_out);487_motors.set_pitch(pitch_out);488489// Piro-Comp, or Pirouette Compensation is a pre-compensation calculation, which basically rotates the Roll and Pitch Rate I-terms as the490// helicopter rotates in yaw. Much of the built-up I-term is needed to tip the disk into the incoming wind. Fast yawing can create an instability491// as the built-up I-term in one axis must be reduced, while the other increases. This helps solve that by rotating the I-terms before the error occurs.492// It does assume that the rotor aerodynamics and mechanics are essentially symmetrical about the main shaft, which is a generally valid assumption.493if (_piro_comp_enabled) {494495// used to hold current I-terms while doing piro comp:496const float piro_roll_i = _pid_rate_roll.get_i();497const float piro_pitch_i = _pid_rate_pitch.get_i();498499Vector2f yawratevector;500yawratevector.x = cosf(-rate_rads.z * _dt);501yawratevector.y = sinf(-rate_rads.z * _dt);502yawratevector.normalize();503504_pid_rate_roll.set_integrator(piro_roll_i * yawratevector.x - piro_pitch_i * yawratevector.y);505_pid_rate_pitch.set_integrator(piro_pitch_i * yawratevector.x + piro_roll_i * yawratevector.y);506}507508}509510// rate_bf_to_motor_yaw - ask the rate controller to calculate the motor outputs to achieve the target rate in radians/second511float AC_AttitudeControl_Heli::rate_target_to_motor_yaw(float rate_yaw_actual_rads, float rate_target_rads)512{513if (!((AP_MotorsHeli&)_motors).rotor_runup_complete()) {514_pid_rate_yaw.update_leaky_i(AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE);515}516517float pid = _pid_rate_yaw.update_all(rate_target_rads, rate_yaw_actual_rads, _dt, _motors.limit.yaw) + _actuator_sysid.z;518519// use pid library to calculate ff520float vff = _pid_rate_yaw.get_ff()*_feedforward_scalar;521522// add feed forward523float yaw_out = pid + vff;524525// constrain output526yaw_out = constrain_float(yaw_out, -AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX);527528// output to motors529return yaw_out;530}531532//533// throttle functions534//535536void AC_AttitudeControl_Heli::set_throttle_out(float throttle_in, bool apply_angle_boost, float filter_cutoff)537{538_throttle_in = throttle_in;539update_althold_lean_angle_max(throttle_in);540541_motors.set_throttle_filter_cutoff(filter_cutoff);542if (apply_angle_boost && !((AP_MotorsHeli&)_motors).in_autorotation()) {543// Apply angle boost544throttle_in = get_throttle_boosted(throttle_in);545} else {546// Clear angle_boost for logging purposes547_angle_boost = 0.0f;548}549_motors.set_throttle(throttle_in);550}551552// returns a throttle including compensation for roll/pitch angle553// throttle value should be 0 ~ 1554float AC_AttitudeControl_Heli::get_throttle_boosted(float throttle_in)555{556if (!_angle_boost_enabled) {557_angle_boost = 0;558return throttle_in;559}560// inverted_factor is 1 for tilt angles below 60 degrees561// inverted_factor changes from 1 to -1 for tilt angles between 60 and 120 degrees562563float cos_tilt = _ahrs.cos_pitch() * _ahrs.cos_roll();564float inverted_factor = constrain_float(2.0f * cos_tilt, -1.0f, 1.0f);565float cos_tilt_target = fabsf(cosf(_thrust_angle));566float boost_factor = 1.0f / constrain_float(cos_tilt_target, 0.1f, 1.0f);567568// angle boost and inverted factor applied about the zero thrust collective569const float coll_mid = ((AP_MotorsHeli&)_motors).get_coll_mid();570float throttle_out = ((throttle_in - coll_mid) * inverted_factor * boost_factor) + coll_mid;571_angle_boost = constrain_float(throttle_out - throttle_in, -1.0f, 1.0f);572return throttle_out;573}574575// get_roll_trim - angle in centi-degrees to be added to roll angle for learn hover collective. Used by helicopter to counter tail rotor thrust in hover576float AC_AttitudeControl_Heli::get_roll_trim_cd()577{578// hover roll trim is given the opposite sign in inverted flight since the tail rotor thrust is pointed in the opposite direction.579float inverted_factor = constrain_float(2.0f * _ahrs.cos_roll(), -1.0f, 1.0f);580return constrain_float(_hover_roll_trim_scalar * _hover_roll_trim * inverted_factor, -1000.0f,1000.0f);581}582583// Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing584void 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)585{586if (_inverted_flight) {587euler_roll_angle_cd = wrap_180_cd(euler_roll_angle_cd + 18000);588}589AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, euler_yaw_rate_cds);590}591592// Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing593void 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)594{595if (_inverted_flight) {596euler_roll_angle_cd = wrap_180_cd(euler_roll_angle_cd + 18000);597}598AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, euler_yaw_angle_cd, slew_yaw);599}600601void AC_AttitudeControl_Heli::set_notch_sample_rate(float sample_rate)602{603#if AP_FILTER_ENABLED604_pid_rate_roll.set_notch_sample_rate(sample_rate);605_pid_rate_pitch.set_notch_sample_rate(sample_rate);606_pid_rate_yaw.set_notch_sample_rate(sample_rate);607#endif608}609610// Command a thrust vector and heading rate611void AC_AttitudeControl_Heli::input_thrust_vector_rate_heading(const Vector3f& thrust_vector, float heading_rate_cds, bool slew_yaw)612{613614if (!_inverted_flight) {615AC_AttitudeControl::input_thrust_vector_rate_heading(thrust_vector, heading_rate_cds, slew_yaw);616return;617}618// convert thrust vector to a roll and pitch angles619// this negates the advantage of using thrust vector control, but works just fine620Vector3f angle_target = attitude_from_thrust_vector(thrust_vector, _ahrs.yaw).to_vector312();621622float euler_roll_angle_cd = degrees(angle_target.x) * 100.0f;623euler_roll_angle_cd = wrap_180_cd(euler_roll_angle_cd + 18000);624AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(euler_roll_angle_cd, degrees(angle_target.y) * 100.0f, heading_rate_cds);625}626627// Command a thrust vector, heading and heading rate628void AC_AttitudeControl_Heli::input_thrust_vector_heading(const Vector3f& thrust_vector, float heading_angle_cd, float heading_rate_cds)629{630if (!_inverted_flight) {631AC_AttitudeControl::input_thrust_vector_heading(thrust_vector, heading_angle_cd, heading_rate_cds);632return;633}634// convert thrust vector to a roll and pitch angles635Vector3f angle_target = attitude_from_thrust_vector(thrust_vector, _ahrs.yaw).to_vector312();636637float euler_roll_angle_cd = degrees(angle_target.x) * 100.0f;638euler_roll_angle_cd = wrap_180_cd(euler_roll_angle_cd + 18000);639// note that we are throwing away heading rate here640AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(euler_roll_angle_cd, degrees(angle_target.y) * 100.0f, heading_angle_cd, true);641}642643644