2014-01-29 09:50:32 -04:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
# include "AC_AttitudeControl_Heli.h"
2015-08-11 03:28:41 -03:00
# include <AP_HAL/AP_HAL.h>
2014-01-29 09:50:32 -04:00
// table of user settable parameters
const AP_Param : : GroupInfo AC_AttitudeControl_Heli : : var_info [ ] PROGMEM = {
2015-05-08 02:49:09 -03:00
// parameters from parent vehicle
AP_NESTEDGROUPINFO ( AC_AttitudeControl , 0 ) ,
2015-03-04 03:23:20 -04:00
2014-01-29 09:50:32 -04:00
AP_GROUPEND
} ;
2014-08-20 10:14:25 -03:00
// passthrough_bf_roll_pitch_rate_yaw - passthrough the pilots roll and pitch inputs directly to swashplate for flybar acro mode
void AC_AttitudeControl_Heli : : passthrough_bf_roll_pitch_rate_yaw ( float roll_passthrough , float pitch_passthrough , float yaw_rate_bf )
{
2015-06-22 02:49:25 -03:00
// store roll, pitch and passthroughs
2014-08-20 10:14:25 -03:00
_passthrough_roll = roll_passthrough ;
_passthrough_pitch = pitch_passthrough ;
2015-06-22 02:49:25 -03:00
_passthrough_yaw = yaw_rate_bf ;
2014-08-20 10:14:25 -03:00
// set rate controller to use pass through
_flags_heli . flybar_passthrough = true ;
// set bf rate targets to current body frame rates (i.e. relax and be ready for vehicle to switch out of acro)
_rate_bf_desired . x = _ahrs . get_gyro ( ) . x * AC_ATTITUDE_CONTROL_DEGX100 ;
_rate_bf_desired . y = _ahrs . get_gyro ( ) . y * AC_ATTITUDE_CONTROL_DEGX100 ;
// accel limit desired yaw rate
2015-03-04 03:23:20 -04:00
if ( _accel_yaw_max > 0.0f ) {
float rate_change_limit = _accel_yaw_max * _dt ;
2014-08-20 10:14:25 -03:00
float rate_change = yaw_rate_bf - _rate_bf_desired . z ;
rate_change = constrain_float ( rate_change , - rate_change_limit , rate_change_limit ) ;
_rate_bf_desired . z + = rate_change ;
} else {
_rate_bf_desired . z = yaw_rate_bf ;
}
integrate_bf_rate_error_to_angle_errors ( ) ;
_angle_bf_error . x = 0 ;
_angle_bf_error . y = 0 ;
// update our earth-frame angle targets
Vector3f angle_ef_error ;
2014-08-22 10:50:33 -03:00
if ( frame_conversion_bf_to_ef ( _angle_bf_error , angle_ef_error ) ) {
_angle_ef_target . x = wrap_180_cd_float ( angle_ef_error . x + _ahrs . roll_sensor ) ;
_angle_ef_target . y = wrap_180_cd_float ( angle_ef_error . y + _ahrs . pitch_sensor ) ;
_angle_ef_target . z = wrap_360_cd_float ( angle_ef_error . z + _ahrs . yaw_sensor ) ;
}
2014-08-20 10:14:25 -03:00
// handle flipping over pitch axis
if ( _angle_ef_target . y > 9000.0f ) {
_angle_ef_target . x = wrap_180_cd_float ( _angle_ef_target . x + 18000.0f ) ;
_angle_ef_target . y = wrap_180_cd_float ( 18000.0f - _angle_ef_target . x ) ;
_angle_ef_target . z = wrap_360_cd_float ( _angle_ef_target . z + 18000.0f ) ;
}
if ( _angle_ef_target . y < - 9000.0f ) {
_angle_ef_target . x = wrap_180_cd_float ( _angle_ef_target . x + 18000.0f ) ;
_angle_ef_target . y = wrap_180_cd_float ( - 18000.0f - _angle_ef_target . x ) ;
_angle_ef_target . z = wrap_360_cd_float ( _angle_ef_target . z + 18000.0f ) ;
}
// convert body-frame angle errors to body-frame rate targets
update_rate_bf_targets ( ) ;
// set body-frame roll/pitch rate target to current desired rates which are the vehicle's actual rates
_rate_bf_target . x = _rate_bf_desired . x ;
_rate_bf_target . y = _rate_bf_desired . y ;
// add desired target to yaw
_rate_bf_target . z + = _rate_bf_desired . z ;
}
2014-01-29 09:50:32 -04:00
//
// rate controller (body-frame) methods
//
// rate_controller_run - run lowest level rate controller and send outputs to the motors
// should be called at 100hz or more
void AC_AttitudeControl_Heli : : rate_controller_run ( )
{
// call rate controllers and send output to motors object
2014-08-20 10:14:25 -03:00
// if using a flybar passthrough roll and pitch directly to motors
if ( _flags_heli . flybar_passthrough ) {
_motors . set_roll ( _passthrough_roll ) ;
_motors . set_pitch ( _passthrough_pitch ) ;
} else {
2014-07-03 16:49:48 -03:00
rate_bf_to_motor_roll_pitch ( _rate_bf_target . x , _rate_bf_target . y ) ;
}
2015-06-22 02:49:25 -03:00
if ( _flags_heli . tail_passthrough ) {
_motors . set_yaw ( _passthrough_yaw ) ;
} else {
_motors . set_yaw ( rate_bf_to_motor_yaw ( _rate_bf_target . z ) ) ;
}
2014-01-29 09:50:32 -04:00
}
//
// private methods
//
//
// body-frame rate controller
//
// rate_bf_to_motor_roll_pitch - ask the rate controller to calculate the motor outputs to achieve the target rate in centi-degrees / second
2014-02-10 00:24:11 -04:00
void AC_AttitudeControl_Heli : : rate_bf_to_motor_roll_pitch ( float rate_roll_target_cds , float rate_pitch_target_cds )
2014-01-29 09:50:32 -04:00
{
2014-05-02 21:42:43 -03:00
float roll_pd , roll_i , roll_ff ; // used to capture pid values
float pitch_pd , pitch_i , pitch_ff ; // used to capture pid values
2014-01-29 09:50:32 -04:00
float rate_roll_error , rate_pitch_error ; // simply target_rate - current_rate
float roll_out , pitch_out ;
2014-07-13 04:48:30 -03:00
const Vector3f & gyro = _ahrs . get_gyro ( ) ; // get current rates
2014-01-29 09:50:32 -04:00
// calculate error
rate_roll_error = rate_roll_target_cds - gyro . x * AC_ATTITUDE_CONTROL_DEGX100 ;
rate_pitch_error = rate_pitch_target_cds - gyro . y * AC_ATTITUDE_CONTROL_DEGX100 ;
2015-01-23 06:07:41 -04:00
// input to PID controller
_pid_rate_roll . set_input_filter_all ( rate_roll_error ) ;
2015-05-24 02:52:44 -03:00
_pid_rate_roll . set_desired_rate ( rate_roll_target_cds ) ;
2015-01-23 06:07:41 -04:00
_pid_rate_pitch . set_input_filter_all ( rate_pitch_error ) ;
2015-05-24 02:52:44 -03:00
_pid_rate_pitch . set_desired_rate ( rate_pitch_target_cds ) ;
2015-01-23 06:07:41 -04:00
2014-01-29 09:50:32 -04:00
// call p and d controllers
2015-01-23 06:07:41 -04:00
roll_pd = _pid_rate_roll . get_p ( ) + _pid_rate_roll . get_d ( ) ;
pitch_pd = _pid_rate_pitch . get_p ( ) + _pid_rate_pitch . get_d ( ) ;
2014-01-29 09:50:32 -04:00
// get roll i term
roll_i = _pid_rate_roll . get_integrator ( ) ;
// update i term as long as we haven't breached the limits or the I term will certainly reduce
if ( ! _flags_heli . limit_roll | | ( ( roll_i > 0 & & rate_roll_error < 0 ) | | ( roll_i < 0 & & rate_roll_error > 0 ) ) ) {
2014-01-30 03:58:13 -04:00
if ( ( ( AP_MotorsHeli & ) _motors ) . has_flybar ( ) ) { // Mechanical Flybars get regular integral for rate auto trim
2014-01-29 09:50:32 -04:00
if ( rate_roll_target_cds > - 50 & & rate_roll_target_cds < 50 ) { // Frozen at high rates
2015-01-23 06:07:41 -04:00
roll_i = _pid_rate_roll . get_i ( ) ;
2014-01-29 09:50:32 -04:00
}
} else {
if ( _flags_heli . leaky_i ) {
2015-01-23 06:07:41 -04:00
roll_i = ( ( AC_HELI_PID & ) _pid_rate_roll ) . get_leaky_i ( AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE ) ;
2014-01-29 09:50:32 -04:00
} else {
2015-01-23 06:07:41 -04:00
roll_i = _pid_rate_roll . get_i ( ) ;
2014-01-29 09:50:32 -04:00
}
}
}
// get pitch i term
pitch_i = _pid_rate_pitch . get_integrator ( ) ;
// update i term as long as we haven't breached the limits or the I term will certainly reduce
if ( ! _flags_heli . limit_pitch | | ( ( pitch_i > 0 & & rate_pitch_error < 0 ) | | ( pitch_i < 0 & & rate_pitch_error > 0 ) ) ) {
2014-01-30 03:58:13 -04:00
if ( ( ( AP_MotorsHeli & ) _motors ) . has_flybar ( ) ) { // Mechanical Flybars get regular integral for rate auto trim
2014-01-29 09:50:32 -04:00
if ( rate_pitch_target_cds > - 50 & & rate_pitch_target_cds < 50 ) { // Frozen at high rates
2015-01-23 06:07:41 -04:00
pitch_i = _pid_rate_pitch . get_i ( ) ;
2014-01-29 09:50:32 -04:00
}
} else {
2014-01-30 03:19:59 -04:00
if ( _flags_heli . leaky_i ) {
2015-01-23 06:07:41 -04:00
pitch_i = ( ( AC_HELI_PID & ) _pid_rate_pitch ) . get_leaky_i ( AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE ) ;
2014-01-29 09:50:32 -04:00
} else {
2015-01-23 06:07:41 -04:00
pitch_i = _pid_rate_pitch . get_i ( ) ;
2014-01-29 09:50:32 -04:00
}
}
}
2014-05-02 21:42:43 -03:00
2015-05-22 21:01:03 -03:00
roll_ff = roll_feedforward_filter . apply ( ( ( AC_HELI_PID & ) _pid_rate_roll ) . get_vff ( rate_roll_target_cds ) , _dt ) ;
pitch_ff = pitch_feedforward_filter . apply ( ( ( AC_HELI_PID & ) _pid_rate_pitch ) . get_vff ( rate_pitch_target_cds ) , _dt ) ;
2014-01-29 09:50:32 -04:00
// add feed forward and final output
2014-05-02 21:42:43 -03:00
roll_out = roll_pd + roll_i + roll_ff ;
pitch_out = pitch_pd + pitch_i + pitch_ff ;
2014-01-29 09:50:32 -04:00
// constrain output and update limit flags
2015-05-08 15:41:27 -03:00
if ( fabsf ( roll_out ) > AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX ) {
2014-01-29 09:50:32 -04:00
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 ;
}
2015-05-08 15:41:27 -03:00
if ( fabsf ( pitch_out ) > AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX ) {
2014-01-29 09:50:32 -04:00
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 ;
}
// output to motors
2014-02-10 00:24:11 -04:00
_motors . set_roll ( roll_out ) ;
_motors . set_pitch ( pitch_out ) ;
2014-01-29 09:50:32 -04:00
/*
2014-02-03 07:49:16 -04:00
# if HELI_CC_COMP == ENABLED
static LowPassFilterFloat rate_dynamics_filter ; // Rate Dynamics filter
# endif
# if HELI_CC_COMP == ENABLED
rate_dynamics_filter . set_cutoff_frequency ( 0.01f , 4.0f ) ;
# endif
2014-01-29 09:50:32 -04:00
# if AC_ATTITUDE_HELI_CC_COMP == ENABLED
// Do cross-coupling compensation for low rpm helis
// Credit: Jolyon Saunders
// Note: This is not widely tested at this time. Will not be used by default yet.
float cc_axis_ratio = 2.0f ; // Ratio of compensation on pitch vs roll axes. Number >1 means pitch is affected more than roll
float cc_kp = 0.0002f ; // Compensation p term. Setting this to zero gives h_phang only, while increasing it will increase the p term of correction
float cc_kd = 0.127f ; // Compensation d term, scaled. This accounts for flexing of the blades, dampers etc. Originally was (motors.ext_gyro_gain * 0.0001)
float cc_angle , cc_total_output ;
uint32_t cc_roll_d , cc_pitch_d , cc_sum_d ;
int32_t cc_scaled_roll ;
int32_t cc_roll_output ; // Used to temporarily hold output while rotation is being calculated
int32_t cc_pitch_output ; // Used to temporarily hold output while rotation is being calculated
static int32_t last_roll_output = 0 ;
static int32_t last_pitch_output = 0 ;
cc_scaled_roll = roll_output / cc_axis_ratio ; // apply axis ratio to roll
cc_total_output = safe_sqrt ( cc_scaled_roll * cc_scaled_roll + pitch_output * pitch_output ) * cc_kp ;
// find the delta component
cc_roll_d = ( roll_output - last_roll_output ) / cc_axis_ratio ;
cc_pitch_d = pitch_output - last_pitch_output ;
cc_sum_d = safe_sqrt ( cc_roll_d * cc_roll_d + cc_pitch_d * cc_pitch_d ) ;
// do the magic.
cc_angle = cc_kd * cc_sum_d * cc_total_output - cc_total_output * motors . get_phase_angle ( ) ;
// smooth angle variations, apply constraints
cc_angle = rate_dynamics_filter . apply ( cc_angle ) ;
cc_angle = constrain_float ( cc_angle , - 90.0f , 0.0f ) ;
cc_angle = radians ( cc_angle ) ;
// Make swash rate vector
Vector2f swashratevector ;
swashratevector . x = cosf ( cc_angle ) ;
swashratevector . y = sinf ( cc_angle ) ;
swashratevector . normalize ( ) ;
// rotate the output
cc_roll_output = roll_output ;
cc_pitch_output = pitch_output ;
roll_output = - ( cc_pitch_output * swashratevector . y - cc_roll_output * swashratevector . x ) ;
pitch_output = cc_pitch_output * swashratevector . x + cc_roll_output * swashratevector . y ;
// make current outputs old, for next iteration
last_roll_output = cc_roll_output ;
last_pitch_output = cc_pitch_output ;
# endif // HELI_CC_COMP
# if AC_ATTITUDE_HELI_PIRO_COMP == ENABLED
if ( control_mode < = ACRO ) {
int32_t piro_roll_i , piro_pitch_i ; // used to hold i term while doing prio comp
piro_roll_i = roll_i ;
piro_pitch_i = pitch_i ;
Vector2f yawratevector ;
2015-05-15 12:57:17 -03:00
yawratevector . x = cosf ( - omega . z / 100.0f ) ;
yawratevector . y = sinf ( - omega . z / 100.0f ) ;
2014-01-29 09:50:32 -04:00
yawratevector . normalize ( ) ;
roll_i = piro_roll_i * yawratevector . x - piro_pitch_i * yawratevector . y ;
pitch_i = piro_pitch_i * yawratevector . x + piro_roll_i * yawratevector . y ;
g . pid_rate_pitch . set_integrator ( pitch_i ) ;
g . pid_rate_roll . set_integrator ( roll_i ) ;
}
# endif //HELI_PIRO_COMP
*/
}
// rate_bf_to_motor_yaw - ask the rate controller to calculate the motor outputs to achieve the target rate in centi-degrees / second
float AC_AttitudeControl_Heli : : rate_bf_to_motor_yaw ( float rate_target_cds )
{
2015-05-22 21:01:03 -03:00
float pd , i , vff , aff ; // used to capture pid values for logging
2014-01-29 09:50:32 -04:00
float current_rate ; // this iteration's rate
float rate_error ; // simply target_rate - current_rate
2014-01-30 03:19:59 -04:00
float yaw_out ;
2014-01-29 09:50:32 -04:00
// get current rate
// To-Do: make getting gyro rates more efficient?
2014-07-13 04:48:30 -03:00
current_rate = ( _ahrs . get_gyro ( ) . z * AC_ATTITUDE_CONTROL_DEGX100 ) ;
2014-01-29 09:50:32 -04:00
// calculate error and call pid controller
rate_error = rate_target_cds - current_rate ;
2015-01-23 06:07:41 -04:00
// send input to PID controller
_pid_rate_yaw . set_input_filter_all ( rate_error ) ;
2015-05-24 02:52:44 -03:00
_pid_rate_yaw . set_desired_rate ( rate_target_cds ) ;
2015-01-23 06:07:41 -04:00
// get p and d
pd = _pid_rate_yaw . get_p ( ) + _pid_rate_yaw . get_d ( ) ;
2014-01-29 09:50:32 -04:00
// get i term
i = _pid_rate_yaw . get_integrator ( ) ;
// update i term as long as we haven't breached the limits or the I term will certainly reduce
2014-01-30 03:19:59 -04:00
if ( ! _flags_heli . limit_yaw | | ( ( i > 0 & & rate_error < 0 ) | | ( i < 0 & & rate_error > 0 ) ) ) {
2015-05-28 18:29:27 -03:00
if ( ( ( AP_MotorsHeli & ) _motors ) . rotor_runup_complete ( ) ) {
2015-01-23 06:07:41 -04:00
i = _pid_rate_yaw . get_i ( ) ;
2014-01-30 03:19:59 -04:00
} else {
2015-01-23 06:07:41 -04:00
i = ( ( AC_HELI_PID & ) _pid_rate_yaw ) . get_leaky_i ( AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE ) ; // If motor is not running use leaky I-term to avoid excessive build-up
2014-01-30 03:19:59 -04:00
}
2014-01-29 09:50:32 -04:00
}
2014-05-10 11:17:32 -03:00
2015-05-22 21:01:03 -03:00
vff = yaw_velocity_feedforward_filter . apply ( ( ( AC_HELI_PID & ) _pid_rate_yaw ) . get_vff ( rate_target_cds ) , _dt ) ;
aff = yaw_acceleration_feedforward_filter . apply ( ( ( AC_HELI_PID & ) _pid_rate_yaw ) . get_aff ( rate_target_cds ) , _dt ) ;
2014-05-02 21:42:43 -03:00
2014-01-30 03:19:59 -04:00
// add feed forward
2015-05-22 21:01:03 -03:00
yaw_out = pd + i + vff + aff ;
2014-01-29 09:50:32 -04:00
2014-01-30 03:19:59 -04:00
// constrain output and update limit flag
2015-05-08 15:41:27 -03:00
if ( fabsf ( yaw_out ) > AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX ) {
2014-01-30 03:19:59 -04:00
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 ;
}
2014-01-29 09:50:32 -04:00
2014-01-30 03:19:59 -04:00
// output to motors
return yaw_out ;
2014-01-29 09:50:32 -04:00
}
//
// throttle functions
//
2015-04-03 15:52:20 -03:00
// returns a throttle including compensation for roll/pitch angle
2014-01-29 09:50:32 -04:00
// throttle value should be 0 ~ 1000
2015-04-03 15:52:20 -03:00
float AC_AttitudeControl_Heli : : get_boosted_throttle ( float throttle_in )
2014-01-29 09:50:32 -04:00
{
2014-01-30 20:59:50 -04:00
// no angle boost for trad helis
_angle_boost = 0 ;
2015-04-03 15:52:20 -03:00
return throttle_in ;
2014-01-29 09:50:32 -04:00
}