APM:Copter
mode_acro.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 #include "mode.h"
4 
5 #if MODE_ACRO_ENABLED == ENABLED
6 
7 /*
8  * Init and run calls for acro flight mode
9  */
10 
11 bool Copter::ModeAcro::init(bool ignore_checks)
12 {
13  // if landed and the mode we're switching from does not have manual throttle and the throttle stick is too high
14  if (motors->armed() && ap.land_complete && !copter.flightmode->has_manual_throttle() &&
15  (get_pilot_desired_throttle(channel_throttle->get_control_in(), copter.g2.acro_thr_mid) > copter.get_non_takeoff_throttle())) {
16  return false;
17  }
18  // set target altitude to zero for reporting
20 
21  return true;
22 }
23 
25 {
26  float target_roll, target_pitch, target_yaw;
27  float pilot_throttle_scaled;
28 
29  // if not armed set throttle to zero and exit immediately
30  if (!motors->armed() || ap.throttle_zero || !motors->get_interlock()) {
32  return;
33  }
34 
35  // clear landing flag
36  set_land_complete(false);
37 
38  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
39 
40  // convert the input to the desired body frame rate
42 
43  // get pilot's desired throttle
45 
46  // run attitude controller
47  attitude_control->input_rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw);
48 
49  // output pilot's throttle without angle boost
50  attitude_control->set_throttle_out(pilot_throttle_scaled, false, copter.g.throttle_filt);
51 }
52 
53 
54 // get_pilot_desired_angle_rates - transform pilot's roll pitch and yaw input into a desired lean angle rates
55 // returns desired angle rates in centi-degrees-per-second
56 void Copter::ModeAcro::get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int16_t yaw_in, float &roll_out, float &pitch_out, float &yaw_out)
57 {
58  float rate_limit;
59  Vector3f rate_ef_level, rate_bf_level, rate_bf_request;
60 
62 
63  // apply circular limit to pitch and roll inputs
64  float total_in = norm(pitch_in, roll_in);
65 
66  if (total_in > ROLL_PITCH_YAW_INPUT_MAX) {
67  float ratio = (float)ROLL_PITCH_YAW_INPUT_MAX / total_in;
68  roll_in *= ratio;
69  pitch_in *= ratio;
70  }
71 
72  // calculate roll, pitch rate requests
73  if (g.acro_rp_expo <= 0) {
74  rate_bf_request.x = roll_in * g.acro_rp_p;
75  rate_bf_request.y = pitch_in * g.acro_rp_p;
76  } else {
77  // expo variables
78  float rp_in, rp_in3, rp_out;
79 
80  // range check expo
81  if (g.acro_rp_expo > 1.0f) {
82  g.acro_rp_expo = 1.0f;
83  }
84 
85  // roll expo
86  rp_in = float(roll_in)/ROLL_PITCH_YAW_INPUT_MAX;
87  rp_in3 = rp_in*rp_in*rp_in;
88  rp_out = (g.acro_rp_expo * rp_in3) + ((1.0f - g.acro_rp_expo) * rp_in);
89  rate_bf_request.x = ROLL_PITCH_YAW_INPUT_MAX * rp_out * g.acro_rp_p;
90 
91  // pitch expo
92  rp_in = float(pitch_in)/ROLL_PITCH_YAW_INPUT_MAX;
93  rp_in3 = rp_in*rp_in*rp_in;
94  rp_out = (g.acro_rp_expo * rp_in3) + ((1.0f - g.acro_rp_expo) * rp_in);
95  rate_bf_request.y = ROLL_PITCH_YAW_INPUT_MAX * rp_out * g.acro_rp_p;
96  }
97 
98  // calculate yaw rate request
99  rate_bf_request.z = get_pilot_desired_yaw_rate(yaw_in);
100 
101  // calculate earth frame rate corrections to pull the copter back to level while in ACRO mode
102 
104 
105  // get attitude targets
106  const Vector3f att_target = attitude_control->get_att_target_euler_cd();
107 
108  // Calculate trainer mode earth frame rate command for roll
109  int32_t roll_angle = wrap_180_cd(att_target.x);
111 
112  // Calculate trainer mode earth frame rate command for pitch
113  int32_t pitch_angle = wrap_180_cd(att_target.y);
115 
116  // Calculate trainer mode earth frame rate command for yaw
117  rate_ef_level.z = 0;
118 
119  // Calculate angle limiting earth frame rate commands
121  if (roll_angle > aparm.angle_max){
122  rate_ef_level.x -= g.acro_balance_roll*(roll_angle-aparm.angle_max);
123  }else if (roll_angle < -aparm.angle_max) {
124  rate_ef_level.x -= g.acro_balance_roll*(roll_angle+aparm.angle_max);
125  }
126 
127  if (pitch_angle > aparm.angle_max){
128  rate_ef_level.y -= g.acro_balance_pitch*(pitch_angle-aparm.angle_max);
129  }else if (pitch_angle < -aparm.angle_max) {
130  rate_ef_level.y -= g.acro_balance_pitch*(pitch_angle+aparm.angle_max);
131  }
132  }
133 
134  // convert earth-frame level rates to body-frame level rates
135  attitude_control->euler_rate_to_ang_vel(attitude_control->get_att_target_euler_cd()*radians(0.01f), rate_ef_level, rate_bf_level);
136 
137  // combine earth frame rate corrections with rate requests
139  rate_bf_request.x += rate_bf_level.x;
140  rate_bf_request.y += rate_bf_level.y;
141  rate_bf_request.z += rate_bf_level.z;
142  }else{
143  float acro_level_mix = constrain_float(float(1-MAX(MAX(abs(roll_in), abs(pitch_in)), abs(yaw_in)))/4500.0, 0, 1)*ahrs.cos_pitch();
144 
145  // Scale leveling rates by stick input
146  rate_bf_level = rate_bf_level*acro_level_mix;
147 
148  // Calculate rate limit to prevent change of rate through inverted
149  rate_limit = fabsf(fabsf(rate_bf_request.x)-fabsf(rate_bf_level.x));
150  rate_bf_request.x += rate_bf_level.x;
151  rate_bf_request.x = constrain_float(rate_bf_request.x, -rate_limit, rate_limit);
152 
153  // Calculate rate limit to prevent change of rate through inverted
154  rate_limit = fabsf(fabsf(rate_bf_request.y)-fabsf(rate_bf_level.y));
155  rate_bf_request.y += rate_bf_level.y;
156  rate_bf_request.y = constrain_float(rate_bf_request.y, -rate_limit, rate_limit);
157 
158  // Calculate rate limit to prevent change of rate through inverted
159  rate_limit = fabsf(fabsf(rate_bf_request.z)-fabsf(rate_bf_level.z));
160  rate_bf_request.z += rate_bf_level.z;
161  rate_bf_request.z = constrain_float(rate_bf_request.z, -rate_limit, rate_limit);
162  }
163  }
164 
165  // hand back rate request
166  roll_out = rate_bf_request.x;
167  pitch_out = rate_bf_request.y;
168  yaw_out = rate_bf_request.z;
169 }
170 #endif
float norm(const T first, const U second, const Params... parameters)
void zero_throttle_and_relax_ac()
Definition: mode.cpp:373
virtual bool init(bool ignore_checks) override
Definition: mode_acro.cpp:11
AP_Float acro_balance_roll
Definition: Parameters.h:471
AC_AttitudeControl_t *& attitude_control
Definition: Copter.h:123
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
AP_Float acro_rp_expo
Definition: Parameters.h:474
float get_pilot_desired_yaw_rate(int16_t stick_angle)
Definition: mode.cpp:553
#define ACRO_TRAINER_DISABLED
Definition: defines.h:183
void get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int16_t yaw_in, float &roll_out, float &pitch_out, float &yaw_out)
Definition: mode_acro.cpp:56
int16_t get_control_in() const
#define f(i)
ParametersG2 & g2
Definition: Copter.h:117
int32_t constrain_int32(const int32_t amt, const int32_t low, const int32_t high)
float get_pilot_desired_throttle(int16_t throttle_control, float thr_mid=0.0f)
Definition: mode.cpp:563
DESIRED_THROTTLE_UNLIMITED
float cos_pitch() const
virtual void run() override
Definition: mode_acro.cpp:24
RC_Channel *& channel_roll
Definition: Copter.h:125
AC_PosControl *& pos_control
Definition: Copter.h:120
AP_Float acro_thr_mid
Definition: Parameters.h:556
float constrain_float(const float amt, const float low, const float high)
void set_alt_target(float alt_cm)
MOTOR_CLASS *& motors
Definition: Copter.h:124
#define ROLL_PITCH_YAW_INPUT_MAX
Definition: config.h:545
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
#define ACRO_TRAINER_LIMITED
Definition: defines.h:185
AP_Float acro_balance_pitch
Definition: Parameters.h:472
#define ACRO_LEVEL_MAX_ANGLE
Definition: config.h:467
AP_Int8 acro_trainer
Definition: Parameters.h:473
AP_Float acro_rp_p
Definition: Parameters.h:469
AP_AHRS & ahrs
Definition: Copter.h:122
RC_Channel *& channel_yaw
Definition: Copter.h:128
Parameters & g
Definition: Copter.h:116
void set_land_complete(bool b)
Definition: mode.cpp:582
AP_Vehicle::MultiCopter aparm
Definition: Copter.h:205
RC_Channel *& channel_throttle
Definition: Copter.h:127
RC_Channel *& channel_pitch
Definition: Copter.h:126