APM:Copter
Attitude.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 // get_pilot_desired_heading - transform pilot's yaw input into a
4 // desired yaw rate
5 // returns desired yaw rate in centi-degrees per second
6 float Copter::get_pilot_desired_yaw_rate(int16_t stick_angle)
7 {
8  float yaw_request;
9 
10  // calculate yaw rate request
11  if (g2.acro_y_expo <= 0) {
12  yaw_request = stick_angle * g.acro_yaw_p;
13  } else {
14  // expo variables
15  float y_in, y_in3, y_out;
16 
17  // range check expo
18  if (g2.acro_y_expo > 1.0f || g2.acro_y_expo < 0.5f) {
19  g2.acro_y_expo = 1.0f;
20  }
21 
22  // yaw expo
23  y_in = float(stick_angle)/ROLL_PITCH_YAW_INPUT_MAX;
24  y_in3 = y_in*y_in*y_in;
25  y_out = (g2.acro_y_expo * y_in3) + ((1.0f - g2.acro_y_expo) * y_in);
26  yaw_request = ROLL_PITCH_YAW_INPUT_MAX * y_out * g.acro_yaw_p;
27  }
28  // convert pilot input to the desired yaw rate
29  return yaw_request;
30 }
31 
32 /*************************************************************
33  * throttle control
34  ****************************************************************/
35 
36 // update estimated throttle required to hover (if necessary)
37 // called at 100hz
39 {
40 #if FRAME_CONFIG != HELI_FRAME
41  // if not armed or landed exit
42  if (!motors->armed() || ap.land_complete) {
43  return;
44  }
45 
46  // do not update in manual throttle modes or Drift
48  return;
49  }
50 
51  // do not update while climbing or descending
53  return;
54  }
55 
56  // get throttle output
57  float throttle = motors->get_throttle();
58 
59  // calc average throttle if we are in a level hover
60  if (throttle > 0.0f && abs(climb_rate) < 60 && labs(ahrs.roll_sensor) < 500 && labs(ahrs.pitch_sensor) < 500) {
61  // Can we set the time constant automatically
62  motors->update_throttle_hover(0.01f);
63  }
64 #endif
65 }
66 
67 // set_throttle_takeoff - allows parents to tell throttle controller we are taking off so I terms can be cleared
69 {
70  // tell position controller to reset alt target and reset I terms
72 }
73 
74 // transform pilot's manual throttle input to make hover throttle mid stick
75 // used only for manual throttle modes
76 // thr_mid should be in the range 0 to 1
77 // returns throttle output 0 to 1
78 float Copter::get_pilot_desired_throttle(int16_t throttle_control, float thr_mid)
79 {
80  if (thr_mid <= 0.0f) {
81  thr_mid = motors->get_throttle_hover();
82  }
83 
84  int16_t mid_stick = get_throttle_mid();
85  // protect against unlikely divide by zero
86  if (mid_stick <= 0) {
87  mid_stick = 500;
88  }
89 
90  // ensure reasonable throttle values
91  throttle_control = constrain_int16(throttle_control,0,1000);
92 
93  // calculate normalised throttle input
94  float throttle_in;
95  if (throttle_control < mid_stick) {
96  // below the deadband
97  throttle_in = ((float)throttle_control)*0.5f/(float)mid_stick;
98  }else if(throttle_control > mid_stick) {
99  // above the deadband
100  throttle_in = 0.5f + ((float)(throttle_control-mid_stick)) * 0.5f / (float)(1000-mid_stick);
101  }else{
102  // must be in the deadband
103  throttle_in = 0.5f;
104  }
105 
106  float expo = constrain_float(-(thr_mid-0.5)/0.375, -0.5f, 1.0f);
107  // calculate the output throttle using the given expo function
108  float throttle_out = throttle_in*(1.0f-expo) + expo*throttle_in*throttle_in*throttle_in;
109  return throttle_out;
110 }
111 
112 // get_pilot_desired_climb_rate - transform pilot's throttle input to climb rate in cm/s
113 // without any deadzone at the bottom
114 float Copter::get_pilot_desired_climb_rate(float throttle_control)
115 {
116  // throttle failsafe check
117  if( failsafe.radio ) {
118  return 0.0f;
119  }
120 
121 #if TOY_MODE_ENABLED == ENABLED
122  if (g2.toy_mode.enabled()) {
123  // allow throttle to be reduced after throttle arming and for
124  // slower descent close to the ground
125  g2.toy_mode.throttle_adjust(throttle_control);
126  }
127 #endif
128 
129  float desired_rate = 0.0f;
130  float mid_stick = get_throttle_mid();
131  float deadband_top = mid_stick + g.throttle_deadzone;
132  float deadband_bottom = mid_stick - g.throttle_deadzone;
133 
134  // ensure a reasonable throttle value
135  throttle_control = constrain_float(throttle_control,0.0f,1000.0f);
136 
137  // ensure a reasonable deadzone
139 
140  // check throttle is above, below or in the deadband
141  if (throttle_control < deadband_bottom) {
142  // below the deadband
143  desired_rate = get_pilot_speed_dn() * (throttle_control-deadband_bottom) / deadband_bottom;
144  }else if (throttle_control > deadband_top) {
145  // above the deadband
146  desired_rate = g.pilot_speed_up * (throttle_control-deadband_top) / (1000.0f-deadband_top);
147  }else{
148  // must be in the deadband
149  desired_rate = 0.0f;
150  }
151 
152  return desired_rate;
153 }
154 
155 // get_non_takeoff_throttle - a throttle somewhere between min and mid throttle which should not lead to a takeoff
157 {
158  return MAX(0,motors->get_throttle_hover()/2.0f);
159 }
160 
161 // get_surface_tracking_climb_rate - hold copter at the desired distance above the ground
162 // returns climb rate (in cm/s) which should be passed to the position controller
163 float Copter::get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt)
164 {
165 #if RANGEFINDER_ENABLED == ENABLED
166  static uint32_t last_call_ms = 0;
167  float distance_error;
168  float velocity_correction;
169  float current_alt = inertial_nav.get_altitude();
170 
171  uint32_t now = millis();
172 
173  // reset target altitude if this controller has just been engaged
174  if (now - last_call_ms > RANGEFINDER_TIMEOUT_MS) {
175  target_rangefinder_alt = rangefinder_state.alt_cm + current_alt_target - current_alt;
176  }
177  last_call_ms = now;
178 
179  // adjust rangefinder target alt if motors have not hit their limits
180  if ((target_rate<0 && !motors->limit.throttle_lower) || (target_rate>0 && !motors->limit.throttle_upper)) {
181  target_rangefinder_alt += target_rate * dt;
182  }
183 
184  /*
185  handle rangefinder glitches. When we get a rangefinder reading
186  more than RANGEFINDER_GLITCH_ALT_CM different from the current
187  rangefinder reading then we consider it a glitch and reject
188  until we get RANGEFINDER_GLITCH_NUM_SAMPLES samples in a
189  row. When that happens we reset the target altitude to the new
190  reading
191  */
192  int32_t glitch_cm = rangefinder_state.alt_cm - target_rangefinder_alt;
193  if (glitch_cm >= RANGEFINDER_GLITCH_ALT_CM) {
194  rangefinder_state.glitch_count = MAX(rangefinder_state.glitch_count+1,1);
195  } else if (glitch_cm <= -RANGEFINDER_GLITCH_ALT_CM) {
196  rangefinder_state.glitch_count = MIN(rangefinder_state.glitch_count-1,-1);
197  } else {
198  rangefinder_state.glitch_count = 0;
199  }
200  if (abs(rangefinder_state.glitch_count) >= RANGEFINDER_GLITCH_NUM_SAMPLES) {
201  // shift to the new rangefinder reading
203  rangefinder_state.glitch_count = 0;
204  }
205  if (rangefinder_state.glitch_count != 0) {
206  // we are currently glitching, just use the target rate
207  return target_rate;
208  }
209 
210  // calc desired velocity correction from target rangefinder alt vs actual rangefinder alt (remove the error already passed to Altitude controller to avoid oscillations)
211  distance_error = (target_rangefinder_alt - rangefinder_state.alt_cm) - (current_alt_target - current_alt);
212  velocity_correction = distance_error * g.rangefinder_gain;
213  velocity_correction = constrain_float(velocity_correction, -THR_SURFACE_TRACKING_VELZ_MAX, THR_SURFACE_TRACKING_VELZ_MAX);
214 
215  // return combined pilot climb rate + rate to correct rangefinder alt error
216  return (target_rate + velocity_correction);
217 #else
218  return (float)target_rate;
219 #endif
220 }
221 
222 // get target climb rate reduced to avoid obstacles and altitude fence
224 {
225 #if AC_AVOID_ENABLED == ENABLED
227  return target_rate;
228 #else
229  return target_rate;
230 #endif
231 }
232 
233 // set_accel_throttle_I_from_pilot_throttle - smoothes transition from pilot controlled throttle to autopilot throttle
235 {
236  // get last throttle input sent to attitude controller
237  float pilot_throttle = constrain_float(attitude_control->get_throttle_in(), 0.0f, 1.0f);
238  // shift difference between pilot's throttle and hover throttle into accelerometer I
239  pos_control->get_accel_z_pid().set_integrator((pilot_throttle-motors->get_throttle_hover()) * 1000.0f);
240 }
241 
242 // rotate vector from vehicle's perspective to North-East frame
243 void Copter::rotate_body_frame_to_NE(float &x, float &y)
244 {
245  float ne_x = x*ahrs.cos_yaw() - y*ahrs.sin_yaw();
246  float ne_y = x*ahrs.sin_yaw() + y*ahrs.cos_yaw();
247  x = ne_x;
248  y = ne_y;
249 }
250 
251 // It will return the PILOT_SPEED_DN value if non zero, otherwise if zero it returns the PILOT_SPEED_UP value.
253 {
254  if (g2.pilot_speed_dn == 0) {
255  return abs(g.pilot_speed_up);
256  } else {
257  return abs(g2.pilot_speed_dn);
258  }
259 }
float cos_yaw() const
void init_takeoff()
AP_AHRS_NavEKF ahrs
Definition: Copter.h:255
void rotate_body_frame_to_NE(float &x, float &y)
Definition: Attitude.cpp:243
AC_AttitudeControl_t * attitude_control
Definition: Copter.h:492
void set_throttle_takeoff()
Definition: Attitude.cpp:68
float get_altitude() const
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
#define RANGEFINDER_TIMEOUT_MS
Definition: config.h:100
float sin_yaw() const
float get_pilot_desired_throttle(int16_t throttle_control, float thr_mid=0.0f)
Definition: Attitude.cpp:78
void update_throttle_hover()
Definition: Attitude.cpp:38
ToyMode toy_mode
Definition: Parameters.h:586
struct Copter::@0 rangefinder_state
bool enabled(void) const
Definition: toy_mode.h:14
#define RANGEFINDER_GLITCH_NUM_SAMPLES
Definition: config.h:116
Definition: defines.h:101
AP_Int16 pilot_speed_up
Definition: Parameters.h:416
AP_InertialNav_NavEKF inertial_nav
Definition: Copter.h:483
MOTOR_CLASS * motors
Definition: Copter.h:422
#define THR_SURFACE_TRACKING_VELZ_MAX
Definition: config.h:96
#define MIN(a, b)
int32_t roll_sensor
void set_integrator(float i)
int16_t get_throttle_mid(void)
Definition: radio.cpp:203
int32_t pitch_sensor
AP_Int16 pilot_speed_dn
Definition: Parameters.h:580
bool is_zero(const T fVal1)
Mode * flightmode
Definition: Copter.h:955
#define f(i)
uint32_t millis()
float get_avoidance_adjusted_climbrate(float target_rate)
Definition: Attitude.cpp:223
void set_accel_throttle_I_from_pilot_throttle()
Definition: Attitude.cpp:234
float get_accel_z() const
AP_Int16 throttle_deadzone
Definition: Parameters.h:423
AC_P & get_pos_z_p()
float get_pilot_desired_climb_rate(float throttle_control)
Definition: Attitude.cpp:114
void throttle_adjust(float &throttle_control)
float target_rangefinder_alt
Definition: Copter.h:465
const Vector3f & get_desired_velocity()
Parameters g
Definition: Copter.h:208
float constrain_float(const float amt, const float low, const float high)
int16_t climb_rate
Definition: Copter.h:464
#define ROLL_PITCH_YAW_INPUT_MAX
Definition: config.h:545
AP_Float rangefinder_gain
Definition: Parameters.h:395
struct Copter::@2 failsafe
AC_PosControl * pos_control
Definition: Copter.h:493
AC_Avoid avoid
Definition: Copter.h:532
virtual bool has_manual_throttle() const =0
void adjust_velocity_z(float kP, float accel_cmss, float &climb_rate_cms, float dt)
uint16_t get_pilot_speed_dn()
Definition: Attitude.cpp:252
float get_non_takeoff_throttle()
Definition: Attitude.cpp:156
#define RANGEFINDER_GLITCH_ALT_CM
Definition: config.h:112
ParametersG2 g2
Definition: Copter.h:209
AP_Float acro_y_expo
Definition: Parameters.h:554
AC_PID & get_accel_z_pid()
control_mode_t control_mode
Definition: Copter.h:345
AP_Float acro_yaw_p
Definition: Parameters.h:470
AP_Float & kP()
float get_pilot_desired_yaw_rate(int16_t stick_angle)
Definition: Attitude.cpp:6
float G_Dt
Definition: Copter.h:480
float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt)
Definition: Attitude.cpp:163