APM:Copter
mode_drift.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 #if MODE_DRIFT_ENABLED == ENABLED
4 
5 /*
6  * Init and run calls for drift flight mode
7  */
8 
9 #ifndef DRIFT_SPEEDGAIN
10  # define DRIFT_SPEEDGAIN 8.0f
11 #endif
12 #ifndef DRIFT_SPEEDLIMIT
13  # define DRIFT_SPEEDLIMIT 560.0f
14 #endif
15 
16 #ifndef DRIFT_THR_ASSIST_GAIN
17  # define DRIFT_THR_ASSIST_GAIN 0.0018f // gain controlling amount of throttle assistance
18 #endif
19 
20 #ifndef DRIFT_THR_ASSIST_MAX
21  # define DRIFT_THR_ASSIST_MAX 0.3f // maximum assistance throttle assist will provide
22 #endif
23 
24 #ifndef DRIFT_THR_MIN
25  # define DRIFT_THR_MIN 0.213f // throttle assist will be active when pilot's throttle is above this value
26 #endif
27 #ifndef DRIFT_THR_MAX
28  # define DRIFT_THR_MAX 0.787f // throttle assist will be active when pilot's throttle is below this value
29 #endif
30 
31 // drift_init - initialise drift controller
32 bool Copter::ModeDrift::init(bool ignore_checks)
33 {
34  if (copter.position_ok() || ignore_checks) {
35  return true;
36  }else{
37  return false;
38  }
39 }
40 
41 // drift_run - runs the drift controller
42 // should be called at 100hz or more
44 {
45  static float braker = 0.0f;
46  static float roll_input = 0.0f;
47  float target_roll, target_pitch;
48  float target_yaw_rate;
49  float pilot_throttle_scaled;
50 
51  // if landed and throttle at zero, set throttle to zero and exit immediately
52  if (!motors->armed() || !motors->get_interlock() || (ap.land_complete && ap.throttle_zero)) {
54  return;
55  }
56 
57  // clear landing flag above zero throttle
58  if (!ap.throttle_zero) {
59  set_land_complete(false);
60  }
61 
62  // convert pilot input to lean angles
63  get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, copter.aparm.angle_max);
64 
65  // get pilot's desired throttle
67 
68  // Grab inertial velocity
69  const Vector3f& vel = inertial_nav.get_velocity();
70 
71  // rotate roll, pitch input from north facing to vehicle's perspective
72  float roll_vel = vel.y * ahrs.cos_yaw() - vel.x * ahrs.sin_yaw(); // body roll vel
73  float pitch_vel = vel.y * ahrs.sin_yaw() + vel.x * ahrs.cos_yaw(); // body pitch vel
74 
75  // gain sceduling for Yaw
76  float pitch_vel2 = MIN(fabsf(pitch_vel), 2000);
77  target_yaw_rate = ((float)target_roll/1.0f) * (1.0f - (pitch_vel2 / 5000.0f)) * g.acro_yaw_p;
78 
79  roll_vel = constrain_float(roll_vel, -DRIFT_SPEEDLIMIT, DRIFT_SPEEDLIMIT);
80  pitch_vel = constrain_float(pitch_vel, -DRIFT_SPEEDLIMIT, DRIFT_SPEEDLIMIT);
81 
82  roll_input = roll_input * .96f + (float)channel_yaw->get_control_in() * .04f;
83 
84  //convert user input into desired roll velocity
85  float roll_vel_error = roll_vel - (roll_input / DRIFT_SPEEDGAIN);
86 
87  // Roll velocity is feed into roll acceleration to minimize slip
88  target_roll = roll_vel_error * -DRIFT_SPEEDGAIN;
89  target_roll = constrain_float(target_roll, -4500.0f, 4500.0f);
90 
91  // If we let go of sticks, bring us to a stop
92  if(is_zero(target_pitch)){
93  // .14/ (.03 * 100) = 4.6 seconds till full braking
94  braker += .03f;
95  braker = MIN(braker, DRIFT_SPEEDGAIN);
96  target_pitch = pitch_vel * braker;
97  }else{
98  braker = 0.0f;
99  }
100 
101  // set motors to full range
102  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
103 
104  // call attitude controller
105  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
106 
107  // output pilot's throttle with angle boost
108  attitude_control->set_throttle_out(get_throttle_assist(vel.z, pilot_throttle_scaled), true, g.throttle_filt);
109 }
110 
111 // get_throttle_assist - return throttle output (range 0 ~ 1) based on pilot input and z-axis velocity
112 float Copter::ModeDrift::get_throttle_assist(float velz, float pilot_throttle_scaled)
113 {
114  // throttle assist - adjusts throttle to slow the vehicle's vertical velocity
115  // Only active when pilot's throttle is between 213 ~ 787
116  // Assistance is strongest when throttle is at mid, drops linearly to no assistance at 213 and 787
117  float thr_assist = 0.0f;
118  if (pilot_throttle_scaled > DRIFT_THR_MIN && pilot_throttle_scaled < DRIFT_THR_MAX) {
119  // calculate throttle assist gain
120  thr_assist = 1.2f - ((float)fabsf(pilot_throttle_scaled - 0.5f) / 0.24f);
121  thr_assist = constrain_float(thr_assist, 0.0f, 1.0f) * -DRIFT_THR_ASSIST_GAIN * velz;
122 
123  // ensure throttle assist never adjusts the throttle by more than 300 pwm
124  thr_assist = constrain_float(thr_assist, -DRIFT_THR_ASSIST_MAX, DRIFT_THR_ASSIST_MAX);
125  }
126 
127  return constrain_float(pilot_throttle_scaled + thr_assist, 0.0f, 1.0f);
128 }
129 #endif
float cos_yaw() const
void zero_throttle_and_relax_ac()
Definition: mode.cpp:373
float get_throttle_assist(float velz, float pilot_throttle_scaled)
Definition: mode_drift.cpp:112
AP_Float throttle_filt
Definition: Parameters.h:386
float sin_yaw() const
#define DRIFT_THR_MIN
Definition: mode_drift.cpp:25
#define DRIFT_SPEEDGAIN
Definition: mode_drift.cpp:10
AC_AttitudeControl_t *& attitude_control
Definition: Copter.h:123
#define MIN(a, b)
#define DRIFT_THR_MAX
Definition: mode_drift.cpp:28
int16_t get_control_in() const
bool is_zero(const T fVal1)
#define f(i)
void get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const
Definition: mode.cpp:326
float get_pilot_desired_throttle(int16_t throttle_control, float thr_mid=0.0f)
Definition: mode.cpp:563
DESIRED_THROTTLE_UNLIMITED
#define DRIFT_THR_ASSIST_GAIN
Definition: mode_drift.cpp:17
float constrain_float(const float amt, const float low, const float high)
#define DRIFT_THR_ASSIST_MAX
Definition: mode_drift.cpp:21
MOTOR_CLASS *& motors
Definition: Copter.h:124
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
void run() override
Definition: mode_drift.cpp:43
#define DRIFT_SPEEDLIMIT
Definition: mode_drift.cpp:13
AP_InertialNav & inertial_nav
Definition: Copter.h:121
virtual const Vector3f & get_velocity() const=0
bool init(bool ignore_checks) override
Definition: mode_drift.cpp:32
AP_AHRS & ahrs
Definition: Copter.h:122
RC_Channel *& channel_yaw
Definition: Copter.h:128
AP_Float acro_yaw_p
Definition: Parameters.h:470
Parameters & g
Definition: Copter.h:116
void set_land_complete(bool b)
Definition: mode.cpp:582
RC_Channel *& channel_throttle
Definition: Copter.h:127