APM:Copter
mode_poshold.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 /*
4  * Init and run calls for PosHold flight mode
5  * PosHold tries to improve upon regular loiter by mixing the pilot input with the loiter controller
6  */
7 
8 #define POSHOLD_SPEED_0 10 // speed below which it is always safe to switch to loiter
9 
10 // 400hz loop update rate
11 #define POSHOLD_BRAKE_TIME_ESTIMATE_MAX (600*4) // max number of cycles the brake will be applied before we switch to loiter
12 #define POSHOLD_BRAKE_TO_LOITER_TIMER (150*4) // Number of cycles to transition from brake mode to loiter mode. Must be lower than POSHOLD_LOITER_STAB_TIMER
13 #define POSHOLD_WIND_COMP_START_TIMER (150*4) // Number of cycles to start wind compensation update after loiter is engaged
14 #define POSHOLD_CONTROLLER_TO_PILOT_MIX_TIMER (50*4) // Set it from 100 to 200, the number of centiseconds loiter and manual commands are mixed to make a smooth transition.
15 #define POSHOLD_SMOOTH_RATE_FACTOR 0.0125f // filter applied to pilot's roll/pitch input as it returns to center. A lower number will cause the roll/pitch to return to zero more slowly if the brake_rate is also low.
16 #define POSHOLD_WIND_COMP_TIMER_10HZ 40 // counter value used to reduce wind compensation to 10hz
17 #define LOOP_RATE_FACTOR 4 // used to adapt PosHold params to loop_rate
18 #define TC_WIND_COMP 0.0025f // Time constant for poshold_update_wind_comp_estimate()
19 
20 // definitions that are independent of main loop rate
21 #define POSHOLD_STICK_RELEASE_SMOOTH_ANGLE 1800 // max angle required (in centi-degrees) after which the smooth stick release effect is applied
22 #define POSHOLD_WIND_COMP_ESTIMATE_SPEED_MAX 10 // wind compensation estimates will only run when velocity is at or below this speed in cm/s
23 
24 // mission state enumeration
26  POSHOLD_PILOT_OVERRIDE=0, // pilot is controlling this axis (i.e. roll or pitch)
27  POSHOLD_BRAKE, // this axis is braking towards zero
28  POSHOLD_BRAKE_READY_TO_LOITER, // this axis has completed braking and is ready to enter loiter mode (both modes must be this value before moving to next stage)
29  POSHOLD_BRAKE_TO_LOITER, // both vehicle's axis (roll and pitch) are transitioning from braking to loiter mode (braking and loiter controls are mixed)
30  POSHOLD_LOITER, // both vehicle axis are holding position
31  POSHOLD_CONTROLLER_TO_PILOT_OVERRIDE // pilot has input controls on this axis and this axis is transitioning to pilot override (other axis will transition to brake if no pilot input)
32 };
33 
34 static struct {
35  poshold_rp_mode roll_mode : 3; // roll mode: pilot override, brake or loiter
36  poshold_rp_mode pitch_mode : 3; // pitch mode: pilot override, brake or loiter
37  uint8_t braking_time_updated_roll : 1; // true once we have re-estimated the braking time. This is done once as the vehicle begins to flatten out after braking
38  uint8_t braking_time_updated_pitch : 1; // true once we have re-estimated the braking time. This is done once as the vehicle begins to flatten out after braking
39 
40  // pilot input related variables
41  float pilot_roll; // pilot requested roll angle (filtered to slow returns to zero)
42  float pilot_pitch; // pilot requested roll angle (filtered to slow returns to zero)
43 
44  // braking related variables
45  float brake_gain; // gain used during conversion of vehicle's velocity to lean angle during braking (calculated from brake_rate)
46  int16_t brake_roll; // target roll angle during braking periods
47  int16_t brake_pitch; // target pitch angle during braking periods
48  int16_t brake_timeout_roll; // number of cycles allowed for the braking to complete, this timeout will be updated at half-braking
49  int16_t brake_timeout_pitch; // number of cycles allowed for the braking to complete, this timeout will be updated at half-braking
50  int16_t brake_angle_max_roll; // maximum lean angle achieved during braking. Used to determine when the vehicle has begun to flatten out so that we can re-estimate the braking time
51  int16_t brake_angle_max_pitch; // maximum lean angle achieved during braking Used to determine when the vehicle has begun to flatten out so that we can re-estimate the braking time
52  int16_t brake_to_loiter_timer; // cycles to mix brake and loiter controls in POSHOLD_BRAKE_TO_LOITER
53 
54  // loiter related variables
55  int16_t controller_to_pilot_timer_roll; // cycles to mix controller and pilot controls in POSHOLD_CONTROLLER_TO_PILOT
56  int16_t controller_to_pilot_timer_pitch; // cycles to mix controller and pilot controls in POSHOLD_CONTROLLER_TO_PILOT
57  int16_t controller_final_roll; // final roll angle from controller as we exit brake or loiter mode (used for mixing with pilot input)
58  int16_t controller_final_pitch; // final pitch angle from controller as we exit brake or loiter mode (used for mixing with pilot input)
59 
60  // wind compensation related variables
61  Vector2f wind_comp_ef; // wind compensation in earth frame, filtered lean angles from position controller
62  int16_t wind_comp_roll; // roll angle to compensate for wind
63  int16_t wind_comp_pitch; // pitch angle to compensate for wind
64  uint16_t wind_comp_start_timer; // counter to delay start of wind compensation for a short time after loiter is engaged
65  int8_t wind_comp_timer; // counter to reduce wind comp roll/pitch lean angle calcs to 10hz
66 
67  // final output
68  int16_t roll; // final roll angle sent to attitude controller
69  int16_t pitch; // final pitch angle sent to attitude controller
70 } poshold;
71 
72 // poshold_init - initialise PosHold controller
73 bool Copter::ModePosHold::init(bool ignore_checks)
74 {
75  // fail to initialise PosHold mode if no GPS lock
76  if (!copter.position_ok() && !ignore_checks) {
77  return false;
78  }
79 
80  // initialize vertical speeds and acceleration
83 
84  // initialise position and desired velocity
85  if (!pos_control->is_active_z()) {
88  }
89 
90  // initialise lean angles to current attitude
91  poshold.pilot_roll = 0;
92  poshold.pilot_pitch = 0;
93 
94  // compute brake_gain
95  poshold.brake_gain = (15.0f * (float)g.poshold_brake_rate + 95.0f) / 100.0f;
96 
97  if (ap.land_complete) {
98  // if landed begin in loiter mode
99  poshold.roll_mode = POSHOLD_LOITER;
100  poshold.pitch_mode = POSHOLD_LOITER;
101  // set target to current position
102  // only init here as we can switch to PosHold in flight with a velocity <> 0 that will be used as _last_vel in PosControl and never updated again as we inhibit Reset_I
104  }else{
105  // if not landed start in pilot override to avoid hard twitch
106  poshold.roll_mode = POSHOLD_PILOT_OVERRIDE;
107  poshold.pitch_mode = POSHOLD_PILOT_OVERRIDE;
108  }
109 
110  // initialise wind_comp each time PosHold is switched on
111  poshold.wind_comp_ef.zero();
112  poshold.wind_comp_roll = 0;
113  poshold.wind_comp_pitch = 0;
114  poshold.wind_comp_timer = 0;
115 
116  return true;
117 }
118 
119 // poshold_run - runs the PosHold controller
120 // should be called at 100hz or more
122 {
123  float target_roll, target_pitch; // pilot's roll and pitch angle inputs
124  float target_yaw_rate = 0; // pilot desired yaw rate in centi-degrees/sec
125  float target_climb_rate = 0; // pilot desired climb rate in centimeters/sec
126  float takeoff_climb_rate = 0.0f; // takeoff induced climb rate
127  float brake_to_loiter_mix; // mix of brake and loiter controls. 0 = fully brake controls, 1 = fully loiter controls
128  float controller_to_pilot_roll_mix; // mix of controller and pilot controls. 0 = fully last controller controls, 1 = fully pilot controls
129  float controller_to_pilot_pitch_mix; // mix of controller and pilot controls. 0 = fully last controller controls, 1 = fully pilot controls
130  float vel_fw, vel_right; // vehicle's current velocity in body-frame forward and right directions
131  const Vector3f& vel = inertial_nav.get_velocity();
132 
133  // initialize vertical speeds and acceleration
136 
137  // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
138  if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) {
142  return;
143  }
144 
145  // process pilot inputs
146  if (!copter.failsafe.radio) {
147  // apply SIMPLE mode transform to pilot inputs
149 
150  // get pilot's desired yaw rate
152 
153  // get pilot desired climb rate (for alt-hold mode and take-off)
155  target_climb_rate = constrain_float(target_climb_rate, -get_pilot_speed_dn(), g.pilot_speed_up);
156 
157  // get takeoff adjusted pilot and takeoff climb rates
158  takeoff_get_climb_rates(target_climb_rate, takeoff_climb_rate);
159 
160  // check for take-off
161 #if FRAME_CONFIG == HELI_FRAME
162  // helicopters are held on the ground until rotor speed runup has finished
163  if (ap.land_complete && (takeoff_state.running || (target_climb_rate > 0.0f && motors->rotor_runup_complete()))) {
164 #else
165  if (ap.land_complete && (takeoff_state.running || target_climb_rate > 0.0f)) {
166 #endif
167  if (!takeoff_state.running) {
169  }
170 
171  // indicate we are taking off
172  set_land_complete(false);
173  // clear i term when we're taking off
175  }
176  }
177 
178  // relax loiter target if we might be landed
179  if (ap.land_complete_maybe) {
181  }
182 
183  // if landed initialise loiter targets, set throttle to zero and exit
184  if (ap.land_complete) {
185  // set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
186  if (target_climb_rate < 0.0f) {
187  motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
188  } else {
189  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
190  }
192  attitude_control->reset_rate_controller_I_terms();
193  attitude_control->set_yaw_target_to_current_heading();
194  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0, 0, 0);
195  pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
197  return;
198  }else{
199  // convert pilot input to lean angles
200  get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, attitude_control->get_althold_lean_angle_max());
201 
202  // convert inertial nav earth-frame velocities to body-frame
203  // To-Do: move this to AP_Math (or perhaps we already have a function to do this)
204  vel_fw = vel.x*ahrs.cos_yaw() + vel.y*ahrs.sin_yaw();
205  vel_right = -vel.x*ahrs.sin_yaw() + vel.y*ahrs.cos_yaw();
206 
207  // If not in LOITER, retrieve latest wind compensation lean angles related to current yaw
208  if (poshold.roll_mode != POSHOLD_LOITER || poshold.pitch_mode != POSHOLD_LOITER)
209  poshold_get_wind_comp_lean_angles(poshold.wind_comp_roll, poshold.wind_comp_pitch);
210 
211  // Roll state machine
212  // Each state (aka mode) is responsible for:
213  // 1. dealing with pilot input
214  // 2. calculating the final roll output to the attitude controller
215  // 3. checking if the state (aka mode) should be changed and if 'yes' perform any required initialisation for the new state
216  switch (poshold.roll_mode) {
217 
219  // update pilot desired roll angle using latest radio input
220  // this filters the input so that it returns to zero no faster than the brake-rate
221  poshold_update_pilot_lean_angle(poshold.pilot_roll, target_roll);
222 
223  // switch to BRAKE mode for next iteration if no pilot input
224  if (is_zero(target_roll) && (fabsf(poshold.pilot_roll) < 2 * g.poshold_brake_rate)) {
225  // initialise BRAKE mode
226  poshold.roll_mode = POSHOLD_BRAKE; // Set brake roll mode
227  poshold.brake_roll = 0; // initialise braking angle to zero
228  poshold.brake_angle_max_roll = 0; // reset brake_angle_max so we can detect when vehicle begins to flatten out during braking
229  poshold.brake_timeout_roll = POSHOLD_BRAKE_TIME_ESTIMATE_MAX; // number of cycles the brake will be applied, updated during braking mode.
230  poshold.braking_time_updated_roll = false; // flag the braking time can be re-estimated
231  }
232 
233  // final lean angle should be pilot input plus wind compensation
234  poshold.roll = poshold.pilot_roll + poshold.wind_comp_roll;
235  break;
236 
237  case POSHOLD_BRAKE:
239  // calculate brake_roll angle to counter-act velocity
240  poshold_update_brake_angle_from_velocity(poshold.brake_roll, vel_right);
241 
242  // update braking time estimate
243  if (!poshold.braking_time_updated_roll) {
244  // check if brake angle is increasing
245  if (abs(poshold.brake_roll) >= poshold.brake_angle_max_roll) {
246  poshold.brake_angle_max_roll = abs(poshold.brake_roll);
247  } else {
248  // braking angle has started decreasing so re-estimate braking time
249  poshold.brake_timeout_roll = 1+(uint16_t)(LOOP_RATE_FACTOR*15L*(int32_t)(abs(poshold.brake_roll))/(10L*(int32_t)g.poshold_brake_rate)); // the 1.2 (12/10) factor has to be tuned in flight, here it means 120% of the "normal" time.
250  poshold.braking_time_updated_roll = true;
251  }
252  }
253 
254  // if velocity is very low reduce braking time to 0.5seconds
255  if ((fabsf(vel_right) <= POSHOLD_SPEED_0) && (poshold.brake_timeout_roll > 50*LOOP_RATE_FACTOR)) {
256  poshold.brake_timeout_roll = 50*LOOP_RATE_FACTOR;
257  }
258 
259  // reduce braking timer
260  if (poshold.brake_timeout_roll > 0) {
261  poshold.brake_timeout_roll--;
262  } else {
263  // indicate that we are ready to move to Loiter.
264  // Loiter will only actually be engaged once both roll_mode and pitch_mode are changed to POSHOLD_BRAKE_READY_TO_LOITER
265  // logic for engaging loiter is handled below the roll and pitch mode switch statements
267  }
268 
269  // final lean angle is braking angle + wind compensation angle
270  poshold.roll = poshold.brake_roll + poshold.wind_comp_roll;
271 
272  // check for pilot input
273  if (!is_zero(target_roll)) {
274  // init transition to pilot override
276  }
277  break;
278 
280  case POSHOLD_LOITER:
281  // these modes are combined roll-pitch modes and are handled below
282  break;
283 
285  // update pilot desired roll angle using latest radio input
286  // this filters the input so that it returns to zero no faster than the brake-rate
287  poshold_update_pilot_lean_angle(poshold.pilot_roll, target_roll);
288 
289  // count-down loiter to pilot timer
290  if (poshold.controller_to_pilot_timer_roll > 0) {
291  poshold.controller_to_pilot_timer_roll--;
292  } else {
293  // when timer runs out switch to full pilot override for next iteration
294  poshold.roll_mode = POSHOLD_PILOT_OVERRIDE;
295  }
296 
297  // calculate controller_to_pilot mix ratio
298  controller_to_pilot_roll_mix = (float)poshold.controller_to_pilot_timer_roll / (float)POSHOLD_CONTROLLER_TO_PILOT_MIX_TIMER;
299 
300  // mix final loiter lean angle and pilot desired lean angles
301  poshold.roll = poshold_mix_controls(controller_to_pilot_roll_mix, poshold.controller_final_roll, poshold.pilot_roll + poshold.wind_comp_roll);
302  break;
303  }
304 
305  // Pitch state machine
306  // Each state (aka mode) is responsible for:
307  // 1. dealing with pilot input
308  // 2. calculating the final pitch output to the attitude contpitcher
309  // 3. checking if the state (aka mode) should be changed and if 'yes' perform any required initialisation for the new state
310  switch (poshold.pitch_mode) {
311 
313  // update pilot desired pitch angle using latest radio input
314  // this filters the input so that it returns to zero no faster than the brake-rate
315  poshold_update_pilot_lean_angle(poshold.pilot_pitch, target_pitch);
316 
317  // switch to BRAKE mode for next iteration if no pilot input
318  if (is_zero(target_pitch) && (fabsf(poshold.pilot_pitch) < 2 * g.poshold_brake_rate)) {
319  // initialise BRAKE mode
320  poshold.pitch_mode = POSHOLD_BRAKE; // set brake pitch mode
321  poshold.brake_pitch = 0; // initialise braking angle to zero
322  poshold.brake_angle_max_pitch = 0; // reset brake_angle_max so we can detect when vehicle begins to flatten out during braking
323  poshold.brake_timeout_pitch = POSHOLD_BRAKE_TIME_ESTIMATE_MAX; // number of cycles the brake will be applied, updated during braking mode.
324  poshold.braking_time_updated_pitch = false; // flag the braking time can be re-estimated
325  }
326 
327  // final lean angle should be pilot input plus wind compensation
328  poshold.pitch = poshold.pilot_pitch + poshold.wind_comp_pitch;
329  break;
330 
331  case POSHOLD_BRAKE:
333  // calculate brake_pitch angle to counter-act velocity
335 
336  // update braking time estimate
337  if (!poshold.braking_time_updated_pitch) {
338  // check if brake angle is increasing
339  if (abs(poshold.brake_pitch) >= poshold.brake_angle_max_pitch) {
340  poshold.brake_angle_max_pitch = abs(poshold.brake_pitch);
341  } else {
342  // braking angle has started decreasing so re-estimate braking time
343  poshold.brake_timeout_pitch = 1+(uint16_t)(LOOP_RATE_FACTOR*15L*(int32_t)(abs(poshold.brake_pitch))/(10L*(int32_t)g.poshold_brake_rate)); // the 1.2 (12/10) factor has to be tuned in flight, here it means 120% of the "normal" time.
344  poshold.braking_time_updated_pitch = true;
345  }
346  }
347 
348  // if velocity is very low reduce braking time to 0.5seconds
349  if ((fabsf(vel_fw) <= POSHOLD_SPEED_0) && (poshold.brake_timeout_pitch > 50*LOOP_RATE_FACTOR)) {
350  poshold.brake_timeout_pitch = 50*LOOP_RATE_FACTOR;
351  }
352 
353  // reduce braking timer
354  if (poshold.brake_timeout_pitch > 0) {
355  poshold.brake_timeout_pitch--;
356  } else {
357  // indicate that we are ready to move to Loiter.
358  // Loiter will only actually be engaged once both pitch_mode and pitch_mode are changed to POSHOLD_BRAKE_READY_TO_LOITER
359  // logic for engaging loiter is handled below the pitch and pitch mode switch statements
361  }
362 
363  // final lean angle is braking angle + wind compensation angle
364  poshold.pitch = poshold.brake_pitch + poshold.wind_comp_pitch;
365 
366  // check for pilot input
367  if (!is_zero(target_pitch)) {
368  // init transition to pilot override
370  }
371  break;
372 
374  case POSHOLD_LOITER:
375  // these modes are combined pitch-pitch modes and are handled below
376  break;
377 
379  // update pilot desired pitch angle using latest radio input
380  // this filters the input so that it returns to zero no faster than the brake-rate
381  poshold_update_pilot_lean_angle(poshold.pilot_pitch, target_pitch);
382 
383  // count-down loiter to pilot timer
384  if (poshold.controller_to_pilot_timer_pitch > 0) {
385  poshold.controller_to_pilot_timer_pitch--;
386  } else {
387  // when timer runs out switch to full pilot override for next iteration
388  poshold.pitch_mode = POSHOLD_PILOT_OVERRIDE;
389  }
390 
391  // calculate controller_to_pilot mix ratio
392  controller_to_pilot_pitch_mix = (float)poshold.controller_to_pilot_timer_pitch / (float)POSHOLD_CONTROLLER_TO_PILOT_MIX_TIMER;
393 
394  // mix final loiter lean angle and pilot desired lean angles
395  poshold.pitch = poshold_mix_controls(controller_to_pilot_pitch_mix, poshold.controller_final_pitch, poshold.pilot_pitch + poshold.wind_comp_pitch);
396  break;
397  }
398 
399  // set motors to full range
400  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
401 
402  //
403  // Shared roll & pitch states (POSHOLD_BRAKE_TO_LOITER and POSHOLD_LOITER)
404  //
405 
406  // switch into LOITER mode when both roll and pitch are ready
408  poshold.roll_mode = POSHOLD_BRAKE_TO_LOITER;
409  poshold.pitch_mode = POSHOLD_BRAKE_TO_LOITER;
410  poshold.brake_to_loiter_timer = POSHOLD_BRAKE_TO_LOITER_TIMER;
411  // init loiter controller
413  // set delay to start of wind compensation estimate updates
414  poshold.wind_comp_start_timer = POSHOLD_WIND_COMP_START_TIMER;
415  }
416 
417  // roll-mode is used as the combined roll+pitch mode when in BRAKE_TO_LOITER or LOITER modes
418  if (poshold.roll_mode == POSHOLD_BRAKE_TO_LOITER || poshold.roll_mode == POSHOLD_LOITER) {
419 
420  // force pitch mode to be same as roll_mode just to keep it consistent (it's not actually used in these states)
421  poshold.pitch_mode = poshold.roll_mode;
422 
423  // handle combined roll+pitch mode
424  switch (poshold.roll_mode) {
426  // reduce brake_to_loiter timer
427  if (poshold.brake_to_loiter_timer > 0) {
428  poshold.brake_to_loiter_timer--;
429  } else {
430  // progress to full loiter on next iteration
431  poshold.roll_mode = POSHOLD_LOITER;
432  poshold.pitch_mode = POSHOLD_LOITER;
433  }
434 
435  // calculate percentage mix of loiter and brake control
436  brake_to_loiter_mix = (float)poshold.brake_to_loiter_timer / (float)POSHOLD_BRAKE_TO_LOITER_TIMER;
437 
438  // calculate brake_roll and pitch angles to counter-act velocity
439  poshold_update_brake_angle_from_velocity(poshold.brake_roll, vel_right);
441 
442  // run loiter controller
444 
445  // calculate final roll and pitch output by mixing loiter and brake controls
446  poshold.roll = poshold_mix_controls(brake_to_loiter_mix, poshold.brake_roll + poshold.wind_comp_roll, loiter_nav->get_roll());
447  poshold.pitch = poshold_mix_controls(brake_to_loiter_mix, poshold.brake_pitch + poshold.wind_comp_pitch, loiter_nav->get_pitch());
448 
449  // check for pilot input
450  if (!is_zero(target_roll) || !is_zero(target_pitch)) {
451  // if roll input switch to pilot override for roll
452  if (!is_zero(target_roll)) {
453  // init transition to pilot override
455  // switch pitch-mode to brake (but ready to go back to loiter anytime)
456  // no need to reset poshold.brake_pitch here as wind comp has not been updated since last brake_pitch computation
458  }
459  // if pitch input switch to pilot override for pitch
460  if (!is_zero(target_pitch)) {
461  // init transition to pilot override
463  if (is_zero(target_roll)) {
464  // switch roll-mode to brake (but ready to go back to loiter anytime)
465  // no need to reset poshold.brake_roll here as wind comp has not been updated since last brake_roll computation
467  }
468  }
469  }
470  break;
471 
472  case POSHOLD_LOITER:
473  // run loiter controller
475 
476  // set roll angle based on loiter controller outputs
477  poshold.roll = loiter_nav->get_roll();
478  poshold.pitch = loiter_nav->get_pitch();
479 
480  // update wind compensation estimate
482 
483  // check for pilot input
484  if (!is_zero(target_roll) || !is_zero(target_pitch)) {
485  // if roll input switch to pilot override for roll
486  if (!is_zero(target_roll)) {
487  // init transition to pilot override
489  // switch pitch-mode to brake (but ready to go back to loiter anytime)
491  // reset brake_pitch because wind_comp is now different and should give the compensation of the whole previous loiter angle
492  poshold.brake_pitch = 0;
493  }
494  // if pitch input switch to pilot override for pitch
495  if (!is_zero(target_pitch)) {
496  // init transition to pilot override
498  // if roll not overriden switch roll-mode to brake (but be ready to go back to loiter any time)
499  if (is_zero(target_roll)) {
501  poshold.brake_roll = 0;
502  }
503  }
504  }
505  break;
506 
507  default:
508  // do nothing for uncombined roll and pitch modes
509  break;
510  }
511  }
512 
513  // constrain target pitch/roll angles
514  float angle_max = copter.aparm.angle_max;
515  poshold.roll = constrain_int16(poshold.roll, -angle_max, angle_max);
516  poshold.pitch = constrain_int16(poshold.pitch, -angle_max, angle_max);
517 
518  // update attitude controller targets
519  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(poshold.roll, poshold.pitch, target_yaw_rate);
520 
521  // adjust climb rate using rangefinder
522  if (copter.rangefinder_alt_ok()) {
523  // if rangefinder is ok, use surface tracking
524  target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control->get_alt_target(), G_Dt);
525  }
526 
527  // get avoidance adjusted climb rate
528  target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate);
529 
530  // update altitude target and call position controller
531  pos_control->set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, false);
532  pos_control->add_takeoff_climb_rate(takeoff_climb_rate, G_Dt);
534  }
535 }
536 
537 // poshold_update_pilot_lean_angle - update the pilot's filtered lean angle with the latest raw input received
538 void Copter::ModePosHold::poshold_update_pilot_lean_angle(float &lean_angle_filtered, float &lean_angle_raw)
539 {
540  // if raw input is large or reversing the vehicle's lean angle immediately set the fitlered angle to the new raw angle
541  if ((lean_angle_filtered > 0 && lean_angle_raw < 0) || (lean_angle_filtered < 0 && lean_angle_raw > 0) || (fabsf(lean_angle_raw) > POSHOLD_STICK_RELEASE_SMOOTH_ANGLE)) {
542  lean_angle_filtered = lean_angle_raw;
543  } else {
544  // lean_angle_raw must be pulling lean_angle_filtered towards zero, smooth the decrease
545  if (lean_angle_filtered > 0) {
546  // reduce the filtered lean angle at 5% or the brake rate (whichever is faster).
547  lean_angle_filtered -= MAX((float)lean_angle_filtered * POSHOLD_SMOOTH_RATE_FACTOR, MAX(1, g.poshold_brake_rate/LOOP_RATE_FACTOR));
548  // do not let the filtered angle fall below the pilot's input lean angle.
549  // the above line pulls the filtered angle down and the below line acts as a catch
550  lean_angle_filtered = MAX(lean_angle_filtered, lean_angle_raw);
551  }else{
552  lean_angle_filtered += MAX(-(float)lean_angle_filtered * POSHOLD_SMOOTH_RATE_FACTOR, MAX(1, g.poshold_brake_rate/LOOP_RATE_FACTOR));
553  lean_angle_filtered = MIN(lean_angle_filtered, lean_angle_raw);
554  }
555  }
556 }
557 
558 // poshold_mix_controls - mixes two controls based on the mix_ratio
559 // mix_ratio of 1 = use first_control completely, 0 = use second_control completely, 0.5 = mix evenly
560 int16_t Copter::ModePosHold::poshold_mix_controls(float mix_ratio, int16_t first_control, int16_t second_control)
561 {
562  mix_ratio = constrain_float(mix_ratio, 0.0f, 1.0f);
563  return (int16_t)((mix_ratio * first_control) + ((1.0f-mix_ratio)*second_control));
564 }
565 
566 // poshold_update_brake_angle_from_velocity - updates the brake_angle based on the vehicle's velocity and brake_gain
567 // brake_angle is slewed with the wpnav.poshold_brake_rate and constrained by the wpnav.poshold_braking_angle_max
568 // velocity is assumed to be in the same direction as lean angle so for pitch you should provide the velocity backwards (i.e. -ve forward velocity)
569 void Copter::ModePosHold::poshold_update_brake_angle_from_velocity(int16_t &brake_angle, float velocity)
570 {
571  float lean_angle;
572  int16_t brake_rate = g.poshold_brake_rate;
573 
574  brake_rate /= 4;
575  if (brake_rate <= 0) {
576  brake_rate = 1;
577  }
578 
579  // calculate velocity-only based lean angle
580  if (velocity >= 0) {
581  lean_angle = -poshold.brake_gain * velocity * (1.0f+500.0f/(velocity+60.0f));
582  } else {
583  lean_angle = -poshold.brake_gain * velocity * (1.0f+500.0f/(-velocity+60.0f));
584  }
585 
586  // do not let lean_angle be too far from brake_angle
587  brake_angle = constrain_int16((int16_t)lean_angle, brake_angle - brake_rate, brake_angle + brake_rate);
588 
589  // constrain final brake_angle
590  brake_angle = constrain_int16(brake_angle, -g.poshold_brake_angle_max, g.poshold_brake_angle_max);
591 }
592 
593 // poshold_update_wind_comp_estimate - updates wind compensation estimate
594 // should be called at the maximum loop rate when loiter is engaged
596 {
597  // check wind estimate start has not been delayed
598  if (poshold.wind_comp_start_timer > 0) {
599  poshold.wind_comp_start_timer--;
600  return;
601  }
602 
603  // check horizontal velocity is low
605  return;
606  }
607 
608  // get position controller accel target
609  // To-Do: clean this up by using accessor in loiter controller (or move entire PosHold controller to a library shared with loiter)
610  const Vector3f& accel_target = pos_control->get_accel_target();
611 
612  // update wind compensation in earth-frame lean angles
613  if (is_zero(poshold.wind_comp_ef.x)) {
614  // if wind compensation has not been initialised set it immediately to the pos controller's desired accel in north direction
615  poshold.wind_comp_ef.x = accel_target.x;
616  } else {
617  // low pass filter the position controller's lean angle output
618  poshold.wind_comp_ef.x = (1.0f-TC_WIND_COMP)*poshold.wind_comp_ef.x + TC_WIND_COMP*accel_target.x;
619  }
620  if (is_zero(poshold.wind_comp_ef.y)) {
621  // if wind compensation has not been initialised set it immediately to the pos controller's desired accel in north direction
622  poshold.wind_comp_ef.y = accel_target.y;
623  } else {
624  // low pass filter the position controller's lean angle output
625  poshold.wind_comp_ef.y = (1.0f-TC_WIND_COMP)*poshold.wind_comp_ef.y + TC_WIND_COMP*accel_target.y;
626  }
627 }
628 
629 // poshold_get_wind_comp_lean_angles - retrieve wind compensation angles in body frame roll and pitch angles
630 // should be called at the maximum loop rate
631 void Copter::ModePosHold::poshold_get_wind_comp_lean_angles(int16_t &roll_angle, int16_t &pitch_angle)
632 {
633  // reduce rate to 10hz
634  poshold.wind_comp_timer++;
635  if (poshold.wind_comp_timer < POSHOLD_WIND_COMP_TIMER_10HZ) {
636  return;
637  }
638  poshold.wind_comp_timer = 0;
639 
640  // convert earth frame desired accelerations to body frame roll and pitch lean angles
641  roll_angle = atanf((-poshold.wind_comp_ef.x*ahrs.sin_yaw() + poshold.wind_comp_ef.y*ahrs.cos_yaw())/981)*(18000/M_PI);
642  pitch_angle = atanf(-(poshold.wind_comp_ef.x*ahrs.cos_yaw() + poshold.wind_comp_ef.y*ahrs.sin_yaw())/981)*(18000/M_PI);
643 }
644 
645 // poshold_roll_controller_to_pilot_override - initialises transition from a controller submode (brake or loiter) to a pilot override on roll axis
647 {
649  poshold.controller_to_pilot_timer_roll = POSHOLD_CONTROLLER_TO_PILOT_MIX_TIMER;
650  // initialise pilot_roll to 0, wind_comp will be updated to compensate and poshold_update_pilot_lean_angle function shall not smooth this transition at next iteration. so 0 is the right value
651  poshold.pilot_roll = 0;
652  // store final controller output for mixing with pilot input
653  poshold.controller_final_roll = poshold.roll;
654 }
655 
656 // poshold_pitch_controller_to_pilot_override - initialises transition from a controller submode (brake or loiter) to a pilot override on roll axis
658 {
660  poshold.controller_to_pilot_timer_pitch = POSHOLD_CONTROLLER_TO_PILOT_MIX_TIMER;
661  // initialise pilot_pitch to 0, wind_comp will be updated to compensate and poshold_update_pilot_lean_angle function shall not smooth this transition at next iteration. so 0 is the right value
662  poshold.pilot_pitch = 0;
663  // store final loiter outputs for mixing with pilot input
664  poshold.controller_final_pitch = poshold.pitch;
665 }
float cos_yaw() const
void run() override
DESIRED_SPIN_WHEN_ARMED
void zero_throttle_and_relax_ac()
Definition: mode.cpp:373
int16_t brake_timeout_roll
#define POSHOLD_WIND_COMP_START_TIMER
int16_t wind_comp_pitch
virtual float get_velocity_z() const=0
float get_alt_target() const
int16_t controller_final_roll
#define POSHOLD_STICK_RELEASE_SMOOTH_ANGLE
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
virtual const Vector3f & get_position() const=0
Vector2f wind_comp_ef
#define POSHOLD_CONTROLLER_TO_PILOT_MIX_TIMER
const Vector3f & get_accel_target() const
float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt)
Definition: mode.cpp:548
AP_Int16 poshold_brake_angle_max
Definition: Parameters.h:409
float sin_yaw() const
void takeoff_get_climb_rates(float &pilot_climb_rate, float &takeoff_climb_rate)
Definition: mode.cpp:612
float get_avoidance_adjusted_climbrate(float target_rate)
Definition: mode.cpp:617
int16_t controller_final_pitch
void poshold_roll_controller_to_pilot_override()
void poshold_get_wind_comp_lean_angles(int16_t &roll_angle, int16_t &pitch_angle)
void update_z_controller()
int16_t controller_to_pilot_timer_roll
uint16_t get_pilot_speed_dn(void)
Definition: mode.cpp:622
int8_t wind_comp_timer
int16_t brake_to_loiter_timer
void update_simple_mode(void)
Definition: mode.cpp:573
int16_t brake_roll
AC_AttitudeControl_t *& attitude_control
Definition: Copter.h:123
void init_target(const Vector3f &position)
float get_pilot_desired_climb_rate(float throttle_control)
Definition: mode.cpp:558
AP_Int16 pilot_speed_up
Definition: Parameters.h:416
#define POSHOLD_WIND_COMP_ESTIMATE_SPEED_MAX
#define LOOP_RATE_FACTOR
float get_pilot_desired_yaw_rate(int16_t stick_angle)
Definition: mode.cpp:553
void soften_for_landing()
AP_Int16 pilot_accel_z
Definition: Parameters.h:417
float brake_gain
#define MIN(a, b)
void poshold_pitch_controller_to_pilot_override()
#define TC_WIND_COMP
AP_Float pilot_takeoff_alt
Definition: Parameters.h:389
int16_t controller_to_pilot_timer_pitch
void add_takeoff_climb_rate(float climb_rate_cms, float dt)
int16_t wind_comp_roll
int16_t brake_angle_max_pitch
float pilot_pitch
bool is_active_z() const
void update(float ekfGndSpdLimit, float ekfNavVelGainScaler)
void takeoff_timer_start(float alt_cm)
Definition: mode.cpp:602
int16_t get_control_in() const
void relax_alt_hold_controllers(float throttle_setting)
poshold_rp_mode pitch_mode
bool is_zero(const T fVal1)
#define f(i)
#define POSHOLD_BRAKE_TIME_ESTIMATE_MAX
void set_desired_velocity_z(float vel_z_cms)
void set_speed_z(float speed_down, float speed_up)
uint16_t wind_comp_start_timer
void set_throttle_takeoff(void)
Definition: mode.cpp:597
int16_t pitch
bool init(bool ignore_checks) override
void set_accel_z(float accel_cmss)
#define POSHOLD_BRAKE_TO_LOITER_TIMER
poshold_rp_mode
#define POSHOLD_WIND_COMP_TIMER_10HZ
AP_Int16 poshold_brake_rate
Definition: Parameters.h:408
void get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const
Definition: mode.cpp:326
void poshold_update_wind_comp_estimate()
void poshold_update_pilot_lean_angle(float &lean_angle_filtered, float &lean_angle_raw)
DESIRED_THROTTLE_UNLIMITED
int16_t poshold_mix_controls(float mix_ratio, int16_t first_control, int16_t second_control)
virtual void set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend)
uint8_t braking_time_updated_pitch
AC_PosControl *& pos_control
Definition: Copter.h:120
#define POSHOLD_SMOOTH_RATE_FACTOR
takeoff_state_t & takeoff_state
Definition: Copter.h:131
float constrain_float(const float amt, const float low, const float high)
int16_t brake_angle_max_roll
virtual float get_velocity_xy() const=0
float pilot_roll
int16_t brake_pitch
int16_t roll
MOTOR_CLASS *& motors
Definition: Copter.h:124
int16_t brake_timeout_pitch
static struct @15 poshold
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
float & G_Dt
Definition: Copter.h:129
#define POSHOLD_SPEED_0
Definition: mode_poshold.cpp:8
void poshold_update_brake_angle_from_velocity(int16_t &brake_angle, float velocity)
float & ekfNavVelGainScaler
Definition: Copter.h:137
AP_InertialNav & inertial_nav
Definition: Copter.h:121
virtual const Vector3f & get_velocity() const=0
poshold_rp_mode roll_mode
#define M_PI
AP_AHRS & ahrs
Definition: Copter.h:122
RC_Channel *& channel_yaw
Definition: Copter.h:128
uint8_t braking_time_updated_roll
int32_t get_pitch() const
Parameters & g
Definition: Copter.h:116
int32_t get_roll() const
float & ekfGndSpdLimit
Definition: Copter.h:134
void set_land_complete(bool b)
Definition: mode.cpp:582
RC_Channel *& channel_throttle
Definition: Copter.h:127
AC_Loiter *& loiter_nav
Definition: Copter.h:119
void set_alt_target_to_current_alt()