2016-02-17 21:24:42 -04:00
# pragma once
2014-01-29 09:50:32 -04:00
/// @file AC_AttitudeControl_Heli.h
/// @brief ArduCopter attitude control library for traditional helicopters
2015-08-11 03:28:41 -03:00
# include "AC_AttitudeControl.h"
# include <AP_Motors/AP_MotorsHeli.h>
# include <AC_PID/AC_HELI_PID.h>
# include <Filter/Filter.h>
2014-01-29 09:50:32 -04:00
2016-02-15 02:25:55 -04:00
// default rate controller PID gains
2016-02-17 07:17:15 -04:00
# define AC_ATC_HELI_RATE_RP_P 0.024f
2022-02-14 23:04:36 -04:00
# define AC_ATC_HELI_RATE_RP_I 0.15f
2016-02-17 07:17:15 -04:00
# define AC_ATC_HELI_RATE_RP_D 0.001f
2022-02-14 23:04:36 -04:00
# define AC_ATC_HELI_RATE_RP_IMAX 0.4f
# define AC_ATC_HELI_RATE_RP_FF 0.15f
2016-02-15 02:25:55 -04:00
# define AC_ATC_HELI_RATE_RP_FILT_HZ 20.0f
2016-02-17 07:17:15 -04:00
# define AC_ATC_HELI_RATE_YAW_P 0.18f
# define AC_ATC_HELI_RATE_YAW_I 0.12f
# define AC_ATC_HELI_RATE_YAW_D 0.003f
2022-02-14 23:04:36 -04:00
# define AC_ATC_HELI_RATE_YAW_IMAX 0.4f
2016-02-17 07:17:15 -04:00
# define AC_ATC_HELI_RATE_YAW_FF 0.024f
2016-02-15 02:25:55 -04:00
# define AC_ATC_HELI_RATE_YAW_FILT_HZ 20.0f
2017-12-13 00:36:59 -04:00
# define AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX 0.95f // Heli's use 95% of max collective before limiting frame angle
2014-01-29 09:50:32 -04:00
# define AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE 0.02f
2022-02-14 23:04:36 -04:00
# define AC_ATTITUDE_HELI_RATE_RP_FF_FILTER 20.0f
# define AC_ATTITUDE_HELI_RATE_Y_FF_FILTER 20.0f
2015-10-13 16:02:21 -03:00
# define AC_ATTITUDE_HELI_HOVER_ROLL_TRIM_DEFAULT 300
2016-06-24 04:20:21 -03:00
# define AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD ToRad(30.0f)
2014-01-29 09:50:32 -04:00
class AC_AttitudeControl_Heli : public AC_AttitudeControl {
public :
2017-02-11 04:14:23 -04:00
AC_AttitudeControl_Heli ( AP_AHRS_View & ahrs ,
2022-09-29 20:10:39 -03:00
const AP_MultiCopter & aparm ,
2022-12-05 08:21:43 -04:00
AP_MotorsHeli & motors ) :
AC_AttitudeControl ( ahrs , aparm , motors ) ,
_pid_rate_roll ( AC_ATC_HELI_RATE_RP_P , AC_ATC_HELI_RATE_RP_I , AC_ATC_HELI_RATE_RP_D , AC_ATC_HELI_RATE_RP_FF , AC_ATC_HELI_RATE_RP_IMAX , AC_ATTITUDE_HELI_RATE_RP_FF_FILTER , AC_ATC_HELI_RATE_RP_FILT_HZ , 0.0f ) ,
_pid_rate_pitch ( AC_ATC_HELI_RATE_RP_P , AC_ATC_HELI_RATE_RP_I , AC_ATC_HELI_RATE_RP_D , AC_ATC_HELI_RATE_RP_FF , AC_ATC_HELI_RATE_RP_IMAX , AC_ATTITUDE_HELI_RATE_RP_FF_FILTER , AC_ATC_HELI_RATE_RP_FILT_HZ , 0.0f ) ,
_pid_rate_yaw ( AC_ATC_HELI_RATE_YAW_P , AC_ATC_HELI_RATE_YAW_I , AC_ATC_HELI_RATE_YAW_D , AC_ATC_HELI_RATE_YAW_FF , AC_ATC_HELI_RATE_YAW_IMAX , AC_ATTITUDE_HELI_RATE_Y_FF_FILTER , AC_ATC_HELI_RATE_YAW_FILT_HZ , 0.0f )
2015-09-21 23:08:49 -03:00
{
2014-01-29 09:50:32 -04:00
AP_Param : : setup_object_defaults ( this , var_info ) ;
2015-09-21 23:08:49 -03:00
// initialise flags
_flags_heli . limit_roll = false ;
_flags_heli . limit_pitch = false ;
_flags_heli . limit_yaw = false ;
_flags_heli . leaky_i = true ;
_flags_heli . flybar_passthrough = false ;
_flags_heli . tail_passthrough = false ;
2015-09-21 23:35:53 -03:00
_flags_heli . do_piro_comp = false ;
2015-09-21 23:08:49 -03:00
}
2014-01-29 09:50:32 -04:00
2016-02-15 02:25:55 -04:00
// pid accessors
2018-11-07 06:57:10 -04:00
AC_PID & get_rate_roll_pid ( ) override { return _pid_rate_roll ; }
AC_PID & get_rate_pitch_pid ( ) override { return _pid_rate_pitch ; }
AC_PID & get_rate_yaw_pid ( ) override { return _pid_rate_yaw ; }
2016-02-15 02:25:55 -04:00
2014-08-20 10:14:25 -03:00
// passthrough_bf_roll_pitch_rate_yaw - roll and pitch are passed through directly, body-frame rate target for yaw
2017-01-09 03:30:34 -04:00
void passthrough_bf_roll_pitch_rate_yaw ( float roll_passthrough , float pitch_passthrough , float yaw_rate_bf_cds ) override ;
2015-11-20 15:44:29 -04:00
2016-06-24 04:20:21 -03:00
// Integrate vehicle rate into _att_error_rot_vec_rad
void integrate_bf_rate_error_to_angle_errors ( ) ;
2015-11-28 13:56:25 -04:00
// subclass non-passthrough too, for external gyro, no flybar
void input_rate_bf_roll_pitch_yaw ( float roll_rate_bf_cds , float pitch_rate_bf_cds , float yaw_rate_bf_cds ) override ;
2014-08-20 10:14:25 -03:00
2014-01-29 09:50:32 -04:00
// rate_controller_run - run lowest level body-frame rate controller and send outputs to the motors
// should be called at 100hz or more
2018-11-07 06:57:10 -04:00
virtual void rate_controller_run ( ) override ;
2014-01-29 09:50:32 -04:00
2016-05-23 12:12:14 -03:00
// Update Alt_Hold angle maximum
void update_althold_lean_angle_max ( float throttle_in ) override ;
2014-01-29 09:50:32 -04:00
// use_leaky_i - controls whether we use leaky i term for body-frame to motor output stage
2017-01-09 03:30:34 -04:00
void use_leaky_i ( bool leaky_i ) override { _flags_heli . leaky_i = leaky_i ; }
2014-05-10 11:17:32 -03:00
2015-06-22 02:49:25 -03:00
// use_flybar_passthrough - controls whether we pass-through
// control inputs to swash-plate and tail
2017-01-09 03:30:34 -04:00
void use_flybar_passthrough ( bool passthrough , bool tail_passthrough ) override {
2015-06-22 02:49:25 -03:00
_flags_heli . flybar_passthrough = passthrough ;
_flags_heli . tail_passthrough = tail_passthrough ;
}
2014-01-29 09:50:32 -04:00
2015-09-21 23:35:53 -03:00
// do_piro_comp - controls whether piro-comp is active or not
void do_piro_comp ( bool piro_comp ) { _flags_heli . do_piro_comp = piro_comp ; }
2015-10-23 19:40:28 -03:00
// set_hover_roll_scalar - scales Hover Roll Trim parameter. To be used by vehicle code according to vehicle condition.
2017-01-09 03:30:34 -04:00
void set_hover_roll_trim_scalar ( float scalar ) override { _hover_roll_trim_scalar = constrain_float ( scalar , 0.0f , 1.0f ) ; }
2015-10-23 19:40:28 -03:00
2020-11-17 23:38:18 -04:00
// 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 hover
float get_roll_trim_cd ( ) override { return constrain_float ( _hover_roll_trim_scalar * _hover_roll_trim , - 1000.0f , 1000.0f ) ; }
2016-03-21 07:57:39 -03:00
// Set output throttle
void set_throttle_out ( float throttle_in , bool apply_angle_boost , float filt_cutoff ) override ;
2017-08-27 20:48:36 -03:00
// Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing
2017-06-25 11:33:16 -03:00
void input_euler_angle_roll_pitch_euler_rate_yaw ( float euler_roll_angle_cd , float euler_pitch_angle_cd , float euler_yaw_rate_cds ) override ;
2017-08-27 20:48:36 -03:00
// Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing
2017-06-25 11:33:16 -03:00
void input_euler_angle_roll_pitch_yaw ( float euler_roll_angle_cd , float euler_pitch_angle_cd , float euler_yaw_angle_cd , bool slew_yaw ) override ;
2017-08-27 20:48:36 -03:00
// enable/disable inverted flight
void set_inverted_flight ( bool inverted ) override {
_inverted_flight = inverted ;
}
2014-01-29 09:50:32 -04:00
// user settable parameters
static const struct AP_Param : : GroupInfo var_info [ ] ;
private :
// To-Do: move these limits flags into the heli motors class
struct AttControlHeliFlags {
2014-07-03 15:08:32 -03:00
uint8_t limit_roll : 1 ; // 1 if we have requested larger roll angle than swash can physically move
uint8_t limit_pitch : 1 ; // 1 if we have requested larger pitch angle than swash can physically move
uint8_t limit_yaw : 1 ; // 1 if we have requested larger yaw angle than tail servo can physically move
uint8_t leaky_i : 1 ; // 1 if we should use leaky i term for body-frame rate to motor stage
2014-08-20 10:14:25 -03:00
uint8_t flybar_passthrough : 1 ; // 1 if we should pass through pilots roll & pitch input directly to swash-plate
2015-06-22 02:49:25 -03:00
uint8_t tail_passthrough : 1 ; // 1 if we should pass through pilots yaw input to tail
2015-09-21 23:35:53 -03:00
uint8_t do_piro_comp : 1 ; // 1 if we should do pirouette compensation on roll/pitch
2014-01-29 09:50:32 -04:00
} _flags_heli ;
//
// body-frame rate controller
//
2015-11-24 17:11:50 -04:00
// rate_bf_to_motor_roll_pitch - ask the rate controller to calculate the motor outputs to achieve the target body-frame rate (in radians/sec) for roll, pitch and yaw
2014-02-10 00:24:11 -04:00
// outputs are sent directly to motor class
2017-03-02 07:49:25 -04:00
void rate_bf_to_motor_roll_pitch ( const Vector3f & rate_rads , float rate_roll_target_rads , float rate_pitch_target_rads ) ;
2019-07-16 03:03:22 -03:00
float rate_target_to_motor_yaw ( float rate_yaw_actual_rads , float rate_yaw_rads ) ;
2014-01-29 09:50:32 -04:00
//
// throttle methods
//
2014-05-10 11:17:32 -03:00
2015-04-24 02:13:29 -03:00
// pass through for roll and pitch
2019-04-04 01:46:06 -03:00
float _passthrough_roll ;
float _passthrough_pitch ;
2015-06-22 02:49:25 -03:00
// pass through for yaw if tail_passthrough is set
2019-04-04 01:46:06 -03:00
float _passthrough_yaw ;
2015-09-21 23:35:53 -03:00
2015-10-13 16:02:21 -03:00
// get_roll_trim - angle in centi-degrees to be added to roll angle. Used by helicopter to counter tail rotor thrust in hover
2018-11-07 06:57:10 -04:00
float get_roll_trim_rad ( ) override { return constrain_float ( radians ( _hover_roll_trim_scalar * _hover_roll_trim * 0.01f ) , - radians ( 10.0f ) , radians ( 10.0f ) ) ; }
2015-10-23 19:40:28 -03:00
// internal variables
float _hover_roll_trim_scalar = 0 ; // scalar used to suppress Hover Roll Trim
2015-10-13 16:02:21 -03:00
2016-06-24 04:20:21 -03:00
// This represents an euler axis-angle rotation vector from the vehicles
// estimated attitude to the reference (setpoint) attitude used in the attitude
// controller, in radians in the vehicle body frame of reference.
Vector3f _att_error_rot_vec_rad ;
2015-09-21 23:35:53 -03:00
// parameters
AP_Int8 _piro_comp_enabled ; // Flybar present or not. Affects attitude controller used during ACRO flight mode
2015-10-13 16:02:21 -03:00
AP_Int16 _hover_roll_trim ; // Angle in centi-degrees used to counter tail rotor thrust in hover
2016-02-15 02:25:55 -04:00
AC_HELI_PID _pid_rate_roll ;
AC_HELI_PID _pid_rate_pitch ;
AC_HELI_PID _pid_rate_yaw ;
2014-07-03 16:49:48 -03:00
2014-01-29 09:50:32 -04:00
} ;