6 * Init and run calls for drift flight mode
9 #ifndef DRIFT_SPEEDGAIN
10 # define DRIFT_SPEEDGAIN 8.0f
12 #ifndef DRIFT_SPEEDLIMIT
13 # define DRIFT_SPEEDLIMIT 560.0f
16 #ifndef DRIFT_THR_ASSIST_GAIN
17 # define DRIFT_THR_ASSIST_GAIN 0.0018f // gain controlling amount of throttle assistance
20 #ifndef DRIFT_THR_ASSIST_MAX
21 # define DRIFT_THR_ASSIST_MAX 0.3f // maximum assistance throttle assist will provide
25 # define DRIFT_THR_MIN 0.213f // throttle assist will be active when pilot's throttle is above this value
28 # define DRIFT_THR_MAX 0.787f // throttle assist will be active when pilot's throttle is below this value
31 // drift_init - initialise drift controller
32 bool ModeDrift::init(bool ignore_checks
)
37 // drift_run - runs the drift controller
38 // should be called at 100hz or more
41 static float braker
= 0.0f
;
42 static float roll_input
= 0.0f
;
44 // convert pilot input to lean angles
45 float target_roll
, target_pitch
;
46 get_pilot_desired_lean_angles(target_roll
, target_pitch
, copter
.aparm
.angle_max
, copter
.aparm
.angle_max
);
48 // Grab inertial velocity
49 const Vector3f
& vel
= inertial_nav
.get_velocity_neu_cms();
51 // rotate roll, pitch input from north facing to vehicle's perspective
52 float roll_vel
= vel
.y
* ahrs
.cos_yaw() - vel
.x
* ahrs
.sin_yaw(); // body roll vel
53 float pitch_vel
= vel
.y
* ahrs
.sin_yaw() + vel
.x
* ahrs
.cos_yaw(); // body pitch vel
55 // gain scheduling for yaw
56 float pitch_vel2
= MIN(fabsf(pitch_vel
), 2000);
57 float target_yaw_rate
= target_roll
* (1.0f
- (pitch_vel2
/ 5000.0f
)) * g2
.command_model_acro_y
.get_rate() / 45.0;
59 roll_vel
= constrain_float(roll_vel
, -DRIFT_SPEEDLIMIT
, DRIFT_SPEEDLIMIT
);
60 pitch_vel
= constrain_float(pitch_vel
, -DRIFT_SPEEDLIMIT
, DRIFT_SPEEDLIMIT
);
62 roll_input
= roll_input
* .96f
+ (float)channel_yaw
->get_control_in() * .04f
;
64 // convert user input into desired roll velocity
65 float roll_vel_error
= roll_vel
- (roll_input
/ DRIFT_SPEEDGAIN
);
67 // roll velocity is feed into roll acceleration to minimize slip
68 target_roll
= roll_vel_error
* -DRIFT_SPEEDGAIN
;
69 target_roll
= constrain_float(target_roll
, -4500.0f
, 4500.0f
);
71 // If we let go of sticks, bring us to a stop
72 if (is_zero(target_pitch
)) {
73 // .14/ (.03 * 100) = 4.6 seconds till full braking
75 braker
= MIN(braker
, DRIFT_SPEEDGAIN
);
76 target_pitch
= pitch_vel
* braker
;
81 if (!motors
->armed()) {
82 // Motors should be Stopped
83 motors
->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN
);
84 } else if (copter
.ap
.throttle_zero
) {
86 motors
->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE
);
88 motors
->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED
);
91 switch (motors
->get_spool_state()) {
92 case AP_Motors::SpoolState::SHUT_DOWN
:
94 attitude_control
->reset_yaw_target_and_rate(false);
95 attitude_control
->reset_rate_controller_I_terms();
98 case AP_Motors::SpoolState::GROUND_IDLE
:
100 attitude_control
->reset_yaw_target_and_rate();
101 attitude_control
->reset_rate_controller_I_terms_smoothly();
104 case AP_Motors::SpoolState::THROTTLE_UNLIMITED
:
105 // clear landing flag above zero throttle
106 if (!motors
->limit
.throttle_lower
) {
107 set_land_complete(false);
111 case AP_Motors::SpoolState::SPOOLING_UP
:
112 case AP_Motors::SpoolState::SPOOLING_DOWN
:
117 // call attitude controller
118 attitude_control
->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll
, target_pitch
, target_yaw_rate
);
120 // output pilot's throttle with angle boost
121 const float assisted_throttle
= get_throttle_assist(vel
.z
, get_pilot_desired_throttle());
122 attitude_control
->set_throttle_out(assisted_throttle
, true, g
.throttle_filt
);
125 // get_throttle_assist - return throttle output (range 0 ~ 1) based on pilot input and z-axis velocity
126 float ModeDrift::get_throttle_assist(float velz
, float pilot_throttle_scaled
)
128 // throttle assist - adjusts throttle to slow the vehicle's vertical velocity
129 // Only active when pilot's throttle is between 213 ~ 787
130 // Assistance is strongest when throttle is at mid, drops linearly to no assistance at 213 and 787
131 float thr_assist
= 0.0f
;
132 if (pilot_throttle_scaled
> DRIFT_THR_MIN
&& pilot_throttle_scaled
< DRIFT_THR_MAX
) {
133 // calculate throttle assist gain
134 thr_assist
= 1.2f
- ((float)fabsf(pilot_throttle_scaled
- 0.5f
) / 0.24f
);
135 thr_assist
= constrain_float(thr_assist
, 0.0f
, 1.0f
) * -DRIFT_THR_ASSIST_GAIN
* velz
;
137 // ensure throttle assist never adjusts the throttle by more than 300 pwm
138 thr_assist
= constrain_float(thr_assist
, -DRIFT_THR_ASSIST_MAX
, DRIFT_THR_ASSIST_MAX
);
141 return constrain_float(pilot_throttle_scaled
+ thr_assist
, 0.0f
, 1.0f
);