Paparazzi UAS  v6.2.0_stable
Paparazzi is a free software Unmanned Aircraft System.
All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
guidance_indi_hybrid.c
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2015 Ewoud Smeur <ewoud.smeur@gmail.com>
3  *
4  * This file is part of paparazzi.
5  *
6  * paparazzi is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2, or (at your option)
9  * any later version.
10  *
11  * paparazzi is distributed in the hope that it will be useful,
12  * but WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU General Public License for more details.
15  *
16  * You should have received a copy of the GNU General Public License
17  * along with paparazzi; see the file COPYING. If not, write to
18  * the Free Software Foundation, 59 Temple Place - Suite 330,
19  * Boston, MA 02111-1307, USA.
20  */
21 
30 #include "generated/airframe.h"
32 #include "modules/ins/ins_int.h"
34 #include "state.h"
35 #include "modules/imu/imu.h"
40 #include "mcu_periph/sys_time.h"
41 #include "autopilot.h"
44 #include "stdio.h"
46 #include "modules/core/abi.h"
48 
49 
50 // The acceleration reference is calculated with these gains. If you use GPS,
51 // they are probably limited by the update rate of your GPS. The default
52 // values are tuned for 4 Hz GPS updates. If you have high speed position updates, the
53 // gains can be higher, depending on the speed of the inner loop.
54 #ifndef GUIDANCE_INDI_SPEED_GAIN
55 #define GUIDANCE_INDI_SPEED_GAIN 1.8
56 #define GUIDANCE_INDI_SPEED_GAINZ 1.8
57 #endif
58 
59 #ifndef GUIDANCE_INDI_POS_GAIN
60 #define GUIDANCE_INDI_POS_GAIN 0.5
61 #define GUIDANCE_INDI_POS_GAINZ 0.5
62 #endif
63 
64 #ifndef GUIDANCE_INDI_MIN_PITCH
65 #define GUIDANCE_INDI_MIN_PITCH -120
66 #define GUIDANCE_INDI_MAX_PITCH 25
67 #endif
68 
69 #ifndef GUIDANCE_INDI_LIFTD_ASQ
70 #define GUIDANCE_INDI_LIFTD_ASQ 0.20
71 #endif
72 
73 /* If lift effectiveness at low airspeed not defined,
74  * just make one interpolation segment that connects to
75  * the quadratic part from 12 m/s onward
76  */
77 #ifndef GUIDANCE_INDI_LIFTD_P50
78 #define GUIDANCE_INDI_LIFTD_P80 (GUIDANCE_INDI_LIFTD_ASQ*12*12)
79 #define GUIDANCE_INDI_LIFTD_P50 (GUIDANCE_INDI_LIFTD_P80/2)
80 #endif
81 
84  .pos_gainz = GUIDANCE_INDI_POS_GAINZ,
85 
86  .speed_gain = GUIDANCE_INDI_SPEED_GAIN,
87  .speed_gainz = GUIDANCE_INDI_SPEED_GAINZ,
88 
89  .heading_bank_gain = GUIDANCE_INDI_HEADING_BANK_GAIN,
90  .liftd_asq = GUIDANCE_INDI_LIFTD_ASQ, // coefficient of airspeed squared
91  .liftd_p80 = GUIDANCE_INDI_LIFTD_P80,
92  .liftd_p50 = GUIDANCE_INDI_LIFTD_P50,
93 };
94 
95 #ifndef GUIDANCE_INDI_MAX_AIRSPEED
96 #error "You must have an airspeed sensor to use this guidance"
97 #endif
98 float guidance_indi_max_airspeed = GUIDANCE_INDI_MAX_AIRSPEED;
99 
100 // Tell the guidance that the airspeed needs to be zeroed.
101 // Recomended to also put GUIDANCE_INDI_NAV_SPEED_MARGIN low in this case.
102 #ifndef GUIDANCE_INDI_ZERO_AIRSPEED
103 #define GUIDANCE_INDI_ZERO_AIRSPEED FALSE
104 #endif
105 
106 // Max ground speed that will be commanded
107 #ifndef GUIDANCE_INDI_NAV_SPEED_MARGIN
108 #define GUIDANCE_INDI_NAV_SPEED_MARGIN 10.0
109 #endif
110 #define NAV_MAX_SPEED (GUIDANCE_INDI_MAX_AIRSPEED + GUIDANCE_INDI_NAV_SPEED_MARGIN)
112 
113 #ifndef MAX_DECELERATION
114 #define MAX_DECELERATION 1.
115 #endif
116 
117 /*Airspeed threshold where making a turn is "worth it"*/
118 #ifndef TURN_AIRSPEED_TH
119 #define TURN_AIRSPEED_TH 10.0
120 #endif
121 
122 /*Boolean to force the heading to a static value (only use for specific experiments)*/
123 bool take_heading_control = false;
124 
125 struct FloatVect3 sp_accel = {0.0,0.0,0.0};
126 #ifdef GUIDANCE_INDI_SPECIFIC_FORCE_GAIN
127 float guidance_indi_specific_force_gain = GUIDANCE_INDI_SPECIFIC_FORCE_GAIN;
128 static void guidance_indi_filter_thrust(void);
129 
130 #ifndef GUIDANCE_INDI_THRUST_DYNAMICS
131 #ifndef STABILIZATION_INDI_ACT_DYN_P
132 #error "You need to define GUIDANCE_INDI_THRUST_DYNAMICS to be able to use indi vertical control"
133 #else // assume that the same actuators are used for thrust as for roll (e.g. quadrotor)
134 #define GUIDANCE_INDI_THRUST_DYNAMICS STABILIZATION_INDI_ACT_DYN_P
135 #endif
136 #endif //GUIDANCE_INDI_THRUST_DYNAMICS
137 
138 #endif //GUIDANCE_INDI_SPECIFIC_FORCE_GAIN
139 
140 #ifndef GUIDANCE_INDI_FILTER_CUTOFF
141 #ifdef STABILIZATION_INDI_FILT_CUTOFF
142 #define GUIDANCE_INDI_FILTER_CUTOFF STABILIZATION_INDI_FILT_CUTOFF
143 #else
144 #define GUIDANCE_INDI_FILTER_CUTOFF 3.0
145 #endif
146 #endif
147 
148 #ifdef GUIDANCE_INDI_LINE_GAIN
149 float guidance_indi_line_gain = GUIDANCE_INDI_LINE_GAIN;
150 #else
152 #endif
153 
154 float inv_eff[4];
155 
156 // Max bank angle in radians
158 
160 struct FloatEulers eulers_zxy;
161 
162 float thrust_act = 0;
168 
170 
171 struct FloatMat33 Ga;
172 struct FloatMat33 Ga_inv;
173 struct FloatVect3 euler_cmd;
174 
176 
178 float thrust_in;
179 
180 struct FloatVect3 gi_speed_sp = {0.0, 0.0, 0.0};
181 
182 #ifndef GUIDANCE_INDI_VEL_SP_ID
183 #define GUIDANCE_INDI_VEL_SP_ID ABI_BROADCAST
184 #endif
186 static void vel_sp_cb(uint8_t sender_id, struct FloatVect3 *vel_sp);
187 struct FloatVect3 indi_vel_sp = {0.0, 0.0, 0.0};
188 float time_of_vel_sp = 0.0;
189 
191 static void guidance_indi_calcg_wing(struct FloatMat33 *Gmat);
192 static float guidance_indi_get_liftd(float pitch, float theta);
193 struct FloatVect3 nav_get_speed_sp_from_go(struct EnuCoor_i target, float pos_gain);
194 struct FloatVect3 nav_get_speed_sp_from_line(struct FloatVect2 line_v_enu, struct FloatVect2 to_end_v_enu, struct EnuCoor_i target, float pos_gain);
195 struct FloatVect3 nav_get_speed_setpoint(float pos_gain);
196 
197 #if PERIODIC_TELEMETRY
199 static void send_guidance_indi_hybrid(struct transport_tx *trans, struct link_device *dev)
200 {
201  pprz_msg_send_GUIDANCE_INDI_HYBRID(trans, dev, AC_ID,
202  &sp_accel.x,
203  &sp_accel.y,
204  &sp_accel.z,
205  &euler_cmd.x,
206  &euler_cmd.y,
207  &euler_cmd.z,
208  &filt_accel_ned[0].o[0],
209  &filt_accel_ned[1].o[0],
210  &filt_accel_ned[2].o[0],
211  &gi_speed_sp.x,
212  &gi_speed_sp.y,
213  &gi_speed_sp.z);
214 }
215 #endif
216 
221 {
222  /*AbiBindMsgACCEL_SP(GUIDANCE_INDI_ACCEL_SP_ID, &accel_sp_ev, accel_sp_cb);*/
223  AbiBindMsgVEL_SP(GUIDANCE_INDI_VEL_SP_ID, &vel_sp_ev, vel_sp_cb);
224 
225  float tau = 1.0/(2.0*M_PI*filter_cutoff);
226  float sample_time = 1.0/PERIODIC_FREQUENCY;
227  for(int8_t i=0; i<3; i++) {
228  init_butterworth_2_low_pass(&filt_accel_ned[i], tau, sample_time, 0.0);
229  }
230  init_butterworth_2_low_pass(&roll_filt, tau, sample_time, 0.0);
231  init_butterworth_2_low_pass(&pitch_filt, tau, sample_time, 0.0);
232  init_butterworth_2_low_pass(&thrust_filt, tau, sample_time, 0.0);
233  init_butterworth_2_low_pass(&accely_filt, tau, sample_time, 0.0);
234 
235 #if PERIODIC_TELEMETRY
236  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_GUIDANCE_INDI_HYBRID, send_guidance_indi_hybrid);
237 #endif
238 }
239 
245  thrust_in = stabilization_cmd[COMMAND_THRUST];
247 
248  float tau = 1.0 / (2.0 * M_PI * filter_cutoff);
249  float sample_time = 1.0 / PERIODIC_FREQUENCY;
250  for (int8_t i = 0; i < 3; i++) {
251  init_butterworth_2_low_pass(&filt_accel_ned[i], tau, sample_time, 0.0);
252  }
256  init_butterworth_2_low_pass(&accely_filt, tau, sample_time, 0.0);
257 }
258 
265 void guidance_indi_run(float *heading_sp) {
266 
267  /*Obtain eulers with zxy rotation order*/
269 
270  /*Calculate the transition percentage so that the ctrl_effecitveness scheduling works*/
273  const int32_t max_offset = ANGLE_BFP_OF_REAL(TRANSITION_MAX_OFFSET);
276 
277  //filter accel to get rid of noise and filter attitude to synchronize with accel
279 
280  //Linear controller to find the acceleration setpoint from position and velocity
281  float pos_x_err = POS_FLOAT_OF_BFP(guidance_h.ref.pos.x) - stateGetPositionNed_f()->x;
282  float pos_y_err = POS_FLOAT_OF_BFP(guidance_h.ref.pos.y) - stateGetPositionNed_f()->y;
284 
285  // First check for velocity setpoint from module
286  float dt = get_sys_time_float() - time_of_vel_sp;
287  // If the input command is not updated after a timeout, switch back to flight plan control
288  if (dt < 0.5) {
292  } else if(autopilot.mode == AP_MODE_NAV) {
294  } else {
295  gi_speed_sp.x = pos_x_err * gih_params.pos_gain;
296  gi_speed_sp.y = pos_y_err * gih_params.pos_gain;
297  gi_speed_sp.z = pos_z_err * gih_params.pos_gainz;
298  }
299 
300  //for rc control horizontal, rotate from body axes to NED
301  float psi = eulers_zxy.psi;
302  /*NAV mode*/
303  float speed_sp_b_x = cosf(psi) * gi_speed_sp.x + sinf(psi) * gi_speed_sp.y;
304  float speed_sp_b_y =-sinf(psi) * gi_speed_sp.x + cosf(psi) * gi_speed_sp.y;
305 
306  // Get airspeed or zero it
307  float airspeed;
309  airspeed = 0.0;
310  } else {
311  airspeed = stateGetAirspeed_f();
312  }
313 
314  struct NedCoor_f *groundspeed = stateGetSpeedNed_f();
315  struct FloatVect2 airspeed_v = {cos(psi)*airspeed, sin(psi)*airspeed};
316  struct FloatVect2 windspeed;
317  VECT2_DIFF(windspeed, *groundspeed, airspeed_v);
318 
319  VECT2_DIFF(desired_airspeed, gi_speed_sp, windspeed); // Use 2d part of gi_speed_sp
320  float norm_des_as = FLOAT_VECT2_NORM(desired_airspeed);
321 
322  // Make turn instead of straight line
323  if((airspeed > TURN_AIRSPEED_TH) && (norm_des_as > (TURN_AIRSPEED_TH+2.0) )) {
324 
325  // Give the wind cancellation priority.
326  if (norm_des_as > guidance_indi_max_airspeed) {
327  float groundspeed_factor = 0.0;
328 
329  // if the wind is faster than we can fly, just fly in the wind direction
331  float av = gi_speed_sp.x * gi_speed_sp.x + gi_speed_sp.y * gi_speed_sp.y;
332  float bv = -2 * (windspeed.x * gi_speed_sp.x + windspeed.y * gi_speed_sp.y);
333  float cv = windspeed.x * windspeed.x + windspeed.y * windspeed.y - guidance_indi_max_airspeed * guidance_indi_max_airspeed;
334 
335  float dv = bv * bv - 4.0 * av * cv;
336 
337  // dv can only be positive, but just in case
338  if(dv < 0.0) {
339  dv = fabs(dv);
340  }
341  float d_sqrt = sqrtf(dv);
342 
343  groundspeed_factor = (-bv + d_sqrt) / (2.0 * av);
344  }
345 
346  desired_airspeed.x = groundspeed_factor * gi_speed_sp.x - windspeed.x;
347  desired_airspeed.y = groundspeed_factor * gi_speed_sp.y - windspeed.y;
348 
349  speed_sp_b_x = guidance_indi_max_airspeed;
350  }
351 
352  // desired airspeed can not be larger than max airspeed
353  speed_sp_b_x = Min(norm_des_as,guidance_indi_max_airspeed);
354 
355  if(force_forward) {
356  speed_sp_b_x = guidance_indi_max_airspeed;
357  }
358 
359  // Calculate accel sp in body axes, because we need to regulate airspeed
360  struct FloatVect2 sp_accel_b;
361  // In turn acceleration proportional to heading diff
362  sp_accel_b.y = atan2(desired_airspeed.y, desired_airspeed.x) - psi;
363  FLOAT_ANGLE_NORMALIZE(sp_accel_b.y);
364  sp_accel_b.y *= gih_params.heading_bank_gain;
365 
366  // Control the airspeed
367  sp_accel_b.x = (speed_sp_b_x - airspeed) * gih_params.speed_gain;
368 
369  sp_accel.x = cosf(psi) * sp_accel_b.x - sinf(psi) * sp_accel_b.y;
370  sp_accel.y = sinf(psi) * sp_accel_b.x + cosf(psi) * sp_accel_b.y;
371 
373  } else { // Go somewhere in the shortest way
374 
375  if(airspeed > 10.0) {
376  // Groundspeed vector in body frame
377  float groundspeed_x = cosf(psi) * stateGetSpeedNed_f()->x + sinf(psi) * stateGetSpeedNed_f()->y;
378  float speed_increment = speed_sp_b_x - groundspeed_x;
379 
380  // limit groundspeed setpoint to max_airspeed + (diff gs and airspeed)
381  if((speed_increment + airspeed) > guidance_indi_max_airspeed) {
382  speed_sp_b_x = guidance_indi_max_airspeed + groundspeed_x - airspeed;
383  }
384  }
385 
386  gi_speed_sp.x = cosf(psi) * speed_sp_b_x - sinf(psi) * speed_sp_b_y;
387  gi_speed_sp.y = sinf(psi) * speed_sp_b_x + cosf(psi) * speed_sp_b_y;
388 
392  }
393 
394  // Bound the acceleration setpoint
395  float accelbound = 3.0 + airspeed/guidance_indi_max_airspeed*5.0;
396  vect_bound_in_2d(&sp_accel, accelbound);
397  /*BoundAbs(sp_accel.x, 3.0 + airspeed/guidance_indi_max_airspeed*6.0);*/
398  /*BoundAbs(sp_accel.y, 3.0 + airspeed/guidance_indi_max_airspeed*6.0);*/
399  BoundAbs(sp_accel.z, 3.0);
400 
401 #if GUIDANCE_INDI_RC_DEBUG
402 #warning "GUIDANCE_INDI_RC_DEBUG lets you control the accelerations via RC, but disables autonomous flight!"
403  //for rc control horizontal, rotate from body axes to NED
404  float psi = eulers_zxy.psi;
405  float rc_x = -(radio_control.values[RADIO_PITCH]/9600.0)*8.0;
406  float rc_y = (radio_control.values[RADIO_ROLL]/9600.0)*8.0;
407  sp_accel.x = cosf(psi) * rc_x - sinf(psi) * rc_y;
408  sp_accel.y = sinf(psi) * rc_x + cosf(psi) * rc_y;
409 
410  //for rc vertical control
411  sp_accel.z = -(radio_control.values[RADIO_THROTTLE]-4500)*8.0/9600.0;
412 #endif
413 
414  //Calculate matrix of partial derivatives
416  //Invert this matrix
417  MAT33_INV(Ga_inv, Ga);
418 
419  struct FloatVect3 accel_filt;
420  accel_filt.x = filt_accel_ned[0].o[0];
421  accel_filt.y = filt_accel_ned[1].o[0];
422  accel_filt.z = filt_accel_ned[2].o[0];
423 
424  struct FloatVect3 a_diff;
425  a_diff.x = sp_accel.x - accel_filt.x;
426  a_diff.y = sp_accel.y - accel_filt.y;
427  a_diff.z = sp_accel.z - accel_filt.z;
428 
429  //Bound the acceleration error so that the linearization still holds
430  Bound(a_diff.x, -6.0, 6.0);
431  Bound(a_diff.y, -6.0, 6.0);
432  Bound(a_diff.z, -9.0, 9.0);
433 
434  //If the thrust to specific force ratio has been defined, include vertical control
435  //else ignore the vertical acceleration error
436 #ifndef GUIDANCE_INDI_SPECIFIC_FORCE_GAIN
437 #ifndef STABILIZATION_ATTITUDE_INDI_FULL
438  a_diff.z = 0.0;
439 #endif
440 #endif
441 
442  //Calculate roll,pitch and thrust command
443  MAT33_VECT3_MUL(euler_cmd, Ga_inv, a_diff);
444 
445  AbiSendMsgTHRUST(THRUST_INCREMENT_ID, euler_cmd.z);
446 
447  //Coordinated turn
448  //feedforward estimate angular rotation omega = g*tan(phi)/v
449  float omega;
450  const float max_phi = RadOfDeg(60.0);
451  float airspeed_turn = airspeed;
452  //We are dividing by the airspeed, so a lower bound is important
453  Bound(airspeed_turn,10.0,30.0);
454 
457 
458  //Bound euler angles to prevent flipping
461 
462  // Use the current roll angle to determine the corresponding heading rate of change.
463  float coordinated_turn_roll = eulers_zxy.phi;
464 
466  coordinated_turn_roll = ((guidance_euler_cmd.phi > 0.0) - (guidance_euler_cmd.phi < 0.0))*guidance_euler_cmd.theta;
467  }
468 
469  if (fabs(coordinated_turn_roll) < max_phi) {
470  omega = 9.81 / airspeed_turn * tanf(coordinated_turn_roll);
471  } else { //max 60 degrees roll
472  omega = 9.81 / airspeed_turn * 1.72305 * ((coordinated_turn_roll > 0.0) - (coordinated_turn_roll < 0.0));
473  }
474 
475 #ifdef FWD_SIDESLIP_GAIN
476  // Add sideslip correction
477  omega -= accely_filt.o[0]*FWD_SIDESLIP_GAIN;
478 #endif
479 
480 // For a hybrid it is important to reduce the sideslip, which is done by changing the heading.
481 // For experiments, it is possible to fix the heading to a different value.
482 #ifndef KNIFE_EDGE_TEST
484  *heading_sp = ANGLE_FLOAT_OF_BFP(nav_heading);
485  } else {
486  *heading_sp += omega / PERIODIC_FREQUENCY;
487  FLOAT_ANGLE_NORMALIZE(*heading_sp);
488  // limit heading setpoint to be within bounds of current heading
489  #ifdef STABILIZATION_ATTITUDE_SP_PSI_DELTA_LIMIT
490  float delta_limit = STABILIZATION_ATTITUDE_SP_PSI_DELTA_LIMIT;
492 
493  float delta_psi = *heading_sp - heading;
494  FLOAT_ANGLE_NORMALIZE(delta_psi);
495  if (delta_psi > delta_limit) {
496  *heading_sp = heading + delta_limit;
497  } else if (delta_psi < -delta_limit) {
498  *heading_sp = heading - delta_limit;
499  }
500  FLOAT_ANGLE_NORMALIZE(*heading_sp);
501  #endif
502  }
503 #endif
504 
505  guidance_euler_cmd.psi = *heading_sp;
506 
507 #ifdef GUIDANCE_INDI_SPECIFIC_FORCE_GAIN
508  guidance_indi_filter_thrust();
509 
510  //Add the increment in specific force * specific_force_to_thrust_gain to the filtered thrust
512  Bound(thrust_in, GUIDANCE_INDI_MIN_THROTTLE, 9600);
513 
514 #if GUIDANCE_INDI_RC_DEBUG
516  thrust_in = 0;
517  }
518 #endif
519 
520  //Overwrite the thrust command from guidance_v
521  stabilization_cmd[COMMAND_THRUST] = thrust_in;
522 #endif
523 
524  // Set the quaternion setpoint from eulers_zxy
525  struct FloatQuat sp_quat;
527  float_quat_normalize(&sp_quat);
529 }
530 
531 #ifdef GUIDANCE_INDI_SPECIFIC_FORCE_GAIN
535 void guidance_indi_filter_thrust(void)
536 {
537  // Actuator dynamics
538  thrust_act = thrust_act + GUIDANCE_INDI_THRUST_DYNAMICS * (thrust_in - thrust_act);
539 
540  // same filter as for the acceleration
542 }
543 #endif
544 
552  struct NedCoor_f *accel = stateGetAccelNed_f();
556 
559 
560  // Propagate filter for sideslip correction
561  float accely = ACCEL_FLOAT_OF_BFP(stateGetAccelBody_i()->y);
563 }
564 
573 
574  /*Pre-calculate sines and cosines*/
575  float sphi = sinf(eulers_zxy.phi);
576  float cphi = cosf(eulers_zxy.phi);
577  float stheta = sinf(eulers_zxy.theta);
578  float ctheta = cosf(eulers_zxy.theta);
579  float spsi = sinf(eulers_zxy.psi);
580  float cpsi = cosf(eulers_zxy.psi);
581  //minus gravity is a guesstimate of the thrust force, thrust measurement would be better
582 
583 #ifndef GUIDANCE_INDI_PITCH_EFF_SCALING
584 #define GUIDANCE_INDI_PITCH_EFF_SCALING 1.0
585 #endif
586 
587  /*Amount of lift produced by the wing*/
588  float pitch_lift = eulers_zxy.theta;
589  Bound(pitch_lift,-M_PI_2,0);
590  float lift = sinf(pitch_lift)*9.81;
591  float T = cosf(pitch_lift)*-9.81;
592 
593  // get the derivative of the lift wrt to theta
595 
596  RMAT_ELMT(*Gmat, 0, 0) = cphi*ctheta*spsi*T + cphi*spsi*lift;
597  RMAT_ELMT(*Gmat, 1, 0) = -cphi*ctheta*cpsi*T - cphi*cpsi*lift;
598  RMAT_ELMT(*Gmat, 2, 0) = -sphi*ctheta*T -sphi*lift;
599  RMAT_ELMT(*Gmat, 0, 1) = (ctheta*cpsi - sphi*stheta*spsi)*T*GUIDANCE_INDI_PITCH_EFF_SCALING + sphi*spsi*liftd;
600  RMAT_ELMT(*Gmat, 1, 1) = (ctheta*spsi + sphi*stheta*cpsi)*T*GUIDANCE_INDI_PITCH_EFF_SCALING - sphi*cpsi*liftd;
601  RMAT_ELMT(*Gmat, 2, 1) = -cphi*stheta*T*GUIDANCE_INDI_PITCH_EFF_SCALING + cphi*liftd;
602  RMAT_ELMT(*Gmat, 0, 2) = stheta*cpsi + sphi*ctheta*spsi;
603  RMAT_ELMT(*Gmat, 1, 2) = stheta*spsi - sphi*ctheta*cpsi;
604  RMAT_ELMT(*Gmat, 2, 2) = cphi*ctheta;
605 }
606 
614 float guidance_indi_get_liftd(float airspeed, float theta) {
615  float liftd = 0.0;
616 
617  if(airspeed < 12) {
618  /* Assume the airspeed is too low to be measured accurately
619  * Use scheduling based on pitch angle instead.
620  * You can define two interpolation segments
621  */
622  float pitch_interp = DegOfRad(theta);
623  const float min_pitch = -80.0;
624  const float middle_pitch = -50.0;
625  const float max_pitch = -20.0;
626 
627  Bound(pitch_interp, min_pitch, max_pitch);
628  if (pitch_interp > middle_pitch) {
629  float ratio = (pitch_interp - max_pitch)/(middle_pitch - max_pitch);
630  liftd = -gih_params.liftd_p50*ratio;
631  } else {
632  float ratio = (pitch_interp - middle_pitch)/(min_pitch - middle_pitch);
634  }
635  } else {
636  liftd = -gih_params.liftd_asq*airspeed*airspeed;
637  }
638 
639  //TODO: bound liftd
640  return liftd;
641 }
642 
652 struct FloatVect3 nav_get_speed_setpoint(float pos_gain) {
653  struct FloatVect3 speed_sp;
656  } else {
658  }
659  return speed_sp;
660 }
661 
671 struct FloatVect3 nav_get_speed_sp_from_line(struct FloatVect2 line_v_enu, struct FloatVect2 to_end_v_enu, struct EnuCoor_i target, float pos_gain) {
672 
673  // enu -> ned
674  struct FloatVect2 line_v = {line_v_enu.y, line_v_enu.x};
675  struct FloatVect2 to_end_v = {to_end_v_enu.y, to_end_v_enu.x};
676 
677  struct NedCoor_f ned_target;
678  // Target in NED instead of ENU
680 
681  // Calculate magnitude of the desired speed vector based on distance to waypoint
682  float dist_to_target = float_vect2_norm(&to_end_v);
683  float desired_speed;
684  if(force_forward) {
685  desired_speed = nav_max_speed;
686  } else {
687  desired_speed = dist_to_target * pos_gain;
688  Bound(desired_speed, 0.0, nav_max_speed);
689  }
690 
691  // Calculate length of line segment
692  float length_line = float_vect2_norm(&line_v);
693  if(length_line < 0.01) {
694  length_line = 0.01;
695  }
696 
697  //Normal vector to the line, with length of the line
698  struct FloatVect2 normalv;
699  VECT2_ASSIGN(normalv, -line_v.y, line_v.x);
700  // Length of normal vector is the same as of the line segment
701  float length_normalv = length_line;
702  if(length_normalv < 0.01) {
703  length_normalv = 0.01;
704  }
705 
706  // Distance along the normal vector
707  float dist_to_line = (to_end_v.x*normalv.x + to_end_v.y*normalv.y)/length_normalv;
708 
709  // Normal vector scaled to be the distance to the line
710  struct FloatVect2 v_to_line, v_along_line;
711  v_to_line.x = dist_to_line*normalv.x/length_normalv*guidance_indi_line_gain;
712  v_to_line.y = dist_to_line*normalv.y/length_normalv*guidance_indi_line_gain;
713 
714  // Depending on the normal vector, the distance could be negative
715  float dist_to_line_abs = fabs(dist_to_line);
716 
717  // The distance that needs to be traveled along the line
718  /*float dist_along_line = (line_v.x*to_end_v.x + line_v.y*to_end_v.y)/length_line;*/
719  v_along_line.x = line_v.x/length_line*50.0;
720  v_along_line.y = line_v.y/length_line*50.0;
721 
722  // Calculate the desired direction to converge to the line
723  struct FloatVect2 direction;
724  VECT2_SMUL(direction, v_along_line, (1.0/(1+dist_to_line_abs*0.05)));
725  VECT2_ADD(direction, v_to_line);
726  float length_direction = float_vect2_norm(&direction);
727  if(length_direction < 0.01) {
728  length_direction = 0.01;
729  }
730 
731  // Scale to have the desired speed
732  struct FloatVect2 final_vector;
733  VECT2_SMUL(final_vector, direction, desired_speed/length_direction);
734 
735  struct FloatVect3 speed_sp_return = {final_vector.x, final_vector.y, gih_params.pos_gainz*(ned_target.z - stateGetPositionNed_f()->z)};
737  speed_sp_return.z = SPEED_FLOAT_OF_BFP(guidance_v_zd_sp);
738  }
739 
740  // Bound vertical speed setpoint
741  if(stateGetAirspeed_f() > 13.0) {
742  Bound(speed_sp_return.z, -4.0, 5.0);
743  } else {
744  Bound(speed_sp_return.z, -nav_climb_vspeed, -nav_descend_vspeed);
745  }
746 
747  return speed_sp_return;
748 }
749 
757 struct FloatVect3 nav_get_speed_sp_from_go(struct EnuCoor_i target, float pos_gain) {
758  // The speed sp that will be returned
759  struct FloatVect3 speed_sp_return;
760  struct NedCoor_f ned_target;
761  // Target in NED instead of ENU
763 
764  // Calculate position error
765  struct FloatVect3 pos_error;
766  struct NedCoor_f *pos = stateGetPositionNed_f();
767  VECT3_DIFF(pos_error, ned_target, *pos);
768 
769  VECT3_SMUL(speed_sp_return, pos_error, pos_gain);
770  speed_sp_return.z = gih_params.pos_gainz*pos_error.z;
771 
773  speed_sp_return.z = SPEED_FLOAT_OF_BFP(guidance_v_zd_sp);
774  }
775 
776  if(force_forward) {
777  vect_scale(&speed_sp_return, nav_max_speed);
778  } else {
779  // Calculate distance to waypoint
780  float dist_to_wp = FLOAT_VECT2_NORM(pos_error);
781 
782  // Calculate max speed to decelerate from
783 
784  // dist_to_wp can only be positive, but just in case
785  float max_speed_decel2 = 2*dist_to_wp*MAX_DECELERATION;
786  if(max_speed_decel2 < 0.0) {
787  max_speed_decel2 = fabs(max_speed_decel2);
788  }
789  float max_speed_decel = sqrtf(max_speed_decel2);
790 
791  // Bound the setpoint velocity vector
792  float max_h_speed = Min(nav_max_speed, max_speed_decel);
793  vect_bound_in_2d(&speed_sp_return, max_h_speed);
794  }
795 
796  // Bound vertical speed setpoint
797  if(stateGetAirspeed_f() > 13.0) {
798  Bound(speed_sp_return.z, -4.0, 5.0);
799  } else {
800  Bound(speed_sp_return.z, -nav_climb_vspeed, -nav_descend_vspeed);
801  }
802 
803  return speed_sp_return;
804 }
805 
809 static void vel_sp_cb(uint8_t sender_id __attribute__((unused)), struct FloatVect3 *vel_sp)
810 {
811  indi_vel_sp.x = vel_sp->x;
812  indi_vel_sp.y = vel_sp->y;
813  indi_vel_sp.z = vel_sp->z;
815 }
Main include for ABI (AirBorneInterface).
Event structure to store callbacks in a linked list.
Definition: abi_common.h:66
#define THRUST_INCREMENT_ID
struct pprz_autopilot autopilot
Global autopilot structure.
Definition: autopilot.c:48
Core autopilot interface common to all firmwares.
uint8_t mode
current autopilot mode
Definition: autopilot.h:63
#define Min(x, y)
Definition: esc_dshot.c:85
float phi
in radians
float theta
in radians
float psi
in radians
static void float_quat_normalize(struct FloatQuat *q)
#define FLOAT_ANGLE_NORMALIZE(_a)
void vect_scale(struct FloatVect3 *vect3, float norm_des)
void float_quat_of_eulers_zxy(struct FloatQuat *q, struct FloatEulers *e)
quat from euler rotation 'ZXY' This rotation order is useful if you need 90 deg pitch
void float_eulers_of_quat_zxy(struct FloatEulers *e, struct FloatQuat *q)
euler rotation 'ZXY' This rotation order is useful if you need 90 deg pitch
static float float_vect2_norm(struct FloatVect2 *v)
#define FLOAT_VECT2_NORM(_v)
void vect_bound_in_2d(struct FloatVect3 *vect3, float bound)
euler angles
Roation quaternion.
#define VECT2_ADD(_a, _b)
Definition: pprz_algebra.h:74
#define VECT2_SMUL(_vo, _vi, _s)
Definition: pprz_algebra.h:98
#define VECT2_DIFF(_c, _a, _b)
Definition: pprz_algebra.h:92
#define MAT33_VECT3_MUL(_vout, _mat, _vin)
Definition: pprz_algebra.h:463
#define MAT33_INV(_minv, _m)
Definition: pprz_algebra.h:489
#define QUAT_BFP_OF_REAL(_qi, _qf)
Definition: pprz_algebra.h:752
#define VECT3_SMUL(_vo, _vi, _s)
Definition: pprz_algebra.h:189
#define VECT3_ASSIGN(_a, _x, _y, _z)
Definition: pprz_algebra.h:125
#define RMAT_ELMT(_rm, _row, _col)
Definition: pprz_algebra.h:660
#define VECT3_DIFF(_c, _a, _b)
Definition: pprz_algebra.h:182
#define VECT2_ASSIGN(_a, _x, _y)
Definition: pprz_algebra.h:62
#define INT_MULT_RSHIFT(_a, _b, _r)
#define ANGLE_BFP_OF_REAL(_af)
#define INT32_PERCENTAGE_FRAC
#define POS_FLOAT_OF_BFP(_ai)
#define SPEED_FLOAT_OF_BFP(_ai)
#define INT32_ANGLE_FRAC
#define BFP_OF_REAL(_vr, _frac)
#define ANGLE_FLOAT_OF_BFP(_ai)
#define ACCEL_FLOAT_OF_BFP(_ai)
vector in East North Up coordinates
static struct NedCoor_f * stateGetAccelNed_f(void)
Get acceleration in NED coordinates (float).
Definition: state.h:1038
static struct FloatEulers * stateGetNedToBodyEulers_f(void)
Get vehicle body attitude euler angles (float).
Definition: state.h:1143
static struct FloatQuat * stateGetNedToBodyQuat_f(void)
Get vehicle body attitude quaternion (float).
Definition: state.h:1131
static struct NedCoor_f * stateGetPositionNed_f(void)
Get position in local NED coordinates (float).
Definition: state.h:710
static struct NedCoor_i * stateGetPositionNed_i(void)
Get position in local NED coordinates (int).
Definition: state.h:665
static struct NedCoor_f * stateGetSpeedNed_f(void)
Get ground speed in local NED coordinates (float).
Definition: state.h:908
static struct Int32Vect3 * stateGetAccelBody_i(void)
Get acceleration in Body coordinates (int).
Definition: state.h:953
static float stateGetAirspeed_f(void)
Get airspeed (float).
Definition: state.h:1407
struct FloatVect3 speed_sp
Definition: guidance_indi.c:76
float guidance_indi_specific_force_gain
#define MAX_DECELERATION
struct FloatVect3 indi_vel_sp
static float guidance_indi_get_liftd(float pitch, float theta)
Get the derivative of lift w.r.t.
Butterworth2LowPass accely_filt
float guidance_indi_line_gain
static void vel_sp_cb(uint8_t sender_id, struct FloatVect3 *vel_sp)
ABI callback that obtains the velocity setpoint from a module.
float time_of_vel_sp
Butterworth2LowPass roll_filt
#define GUIDANCE_INDI_SPEED_GAINZ
struct guidance_indi_hybrid_params gih_params
float thrust_in
struct FloatVect3 gi_speed_sp
float guidance_indi_max_bank
float inv_eff[4]
float nav_max_speed
#define GUIDANCE_INDI_ZERO_AIRSPEED
#define GUIDANCE_INDI_MAX_PITCH
struct FloatVect3 sp_accel
struct FloatEulers guidance_euler_cmd
#define GUIDANCE_INDI_LIFTD_ASQ
struct FloatVect3 nav_get_speed_sp_from_line(struct FloatVect2 line_v_enu, struct FloatVect2 to_end_v_enu, struct EnuCoor_i target, float pos_gain)
follow a line.
float thrust_act
struct FloatMat33 Ga_inv
void guidance_indi_enter(void)
Call upon entering indi guidance.
static void guidance_indi_calcg_wing(struct FloatMat33 *Gmat)
Calculate the matrix of partial derivatives of the roll, pitch and thrust w.r.t.
#define GUIDANCE_INDI_MIN_PITCH
Butterworth2LowPass pitch_filt
#define GUIDANCE_INDI_POS_GAIN
bool take_heading_control
#define GUIDANCE_INDI_LIFTD_P50
static void send_guidance_indi_hybrid(struct transport_tx *trans, struct link_device *dev)
void guidance_indi_init(void)
Init function.
float filter_cutoff
#define GUIDANCE_INDI_FILTER_CUTOFF
struct FloatVect3 euler_cmd
struct FloatVect3 nav_get_speed_sp_from_go(struct EnuCoor_i target, float pos_gain)
Go to a waypoint in the shortest way.
struct FloatEulers eulers_zxy
state eulers in zxy order
#define GUIDANCE_INDI_PITCH_EFF_SCALING
struct FloatMat33 Ga
Butterworth2LowPass filt_accel_ned[3]
#define GUIDANCE_INDI_POS_GAINZ
#define TURN_AIRSPEED_TH
float guidance_indi_max_airspeed
#define NAV_MAX_SPEED
#define GUIDANCE_INDI_VEL_SP_ID
void guidance_indi_propagate_filters(void)
Low pass the accelerometer measurements to remove noise from vibrations.
#define GUIDANCE_INDI_LIFTD_P80
abi_event vel_sp_ev
Butterworth2LowPass thrust_filt
#define GUIDANCE_INDI_SPEED_GAIN
void guidance_indi_run(float *heading_sp)
struct FloatVect3 nav_get_speed_setpoint(float pos_gain)
function that returns a speed setpoint based on flight plan.
struct FloatVect2 desired_airspeed
A guidance mode based on Incremental Nonlinear Dynamic Inversion Come to ICRA2016 to learn more!
Inertial Measurement Unit interface.
INS for rotorcrafts combining vertical and horizontal filters.
Simple first order low pass filter with bilinear transform.
float o[2]
output history
static void init_butterworth_2_low_pass(Butterworth2LowPass *filter, float tau, float sample_time, float value)
Init a second order Butterworth filter.
static float update_butterworth_2_low_pass(Butterworth2LowPass *filter, float value)
Update second order Butterworth low pass filter state with a new value.
Second order low pass filter structure.
uint8_t horizontal_mode
Definition: nav.c:73
#define HORIZONTAL_MODE_ROUTE
Definition: nav.h:93
uint8_t direction
float z
in meters
float x
in meters
float y
in meters
vector in North East Down coordinates Units: meters
struct RadioControl radio_control
Definition: radio_control.c:33
Generic interface for radio control modules.
pprz_t values[RADIO_CONTROL_NB_CHANNEL]
Definition: radio_control.h:67
Some helper functions to check RC sticks.
#define AP_MODE_NAV
int32_t transition_percentage
Definition: guidance_h.c:92
struct HorizontalGuidance guidance_h
Definition: guidance_h.c:90
#define GUIDANCE_H_MAX_BANK
Definition: guidance_h.c:70
Horizontal guidance for rotorcrafts.
struct Int32Vect2 pos
with INT32_POS_FRAC
Definition: guidance_h.h:82
struct HorizontalGuidanceReference ref
reference calculated from setpoints
Definition: guidance_h.h:104
int32_t guidance_v_z_ref
altitude reference in meters.
Definition: guidance_v.c:132
uint8_t guidance_v_mode
Definition: guidance_v.c:103
int32_t guidance_v_zd_sp
vertical speed setpoint in meter/s (input).
Definition: guidance_v.c:130
Vertical guidance for rotorcrafts.
#define GUIDANCE_V_MODE_NAV
Definition: guidance_v.h:40
bool force_forward
Definition: navigation.c:84
float nav_descend_vspeed
Definition: navigation.c:116
int32_t nav_flight_altitude
Definition: navigation.c:120
struct FloatVect2 line_vect to_end_vect
Definition: navigation.c:86
float nav_climb_vspeed
Definition: navigation.c:116
struct EnuCoor_i navigation_target
Definition: navigation.c:96
int32_t nav_heading
with INT32_ANGLE_FRAC
Definition: navigation.c:113
Rotorcraft navigation functions.
#define VERTICAL_MODE_CLIMB
Definition: navigation.h:82
General attitude stabilization interface for rotorcrafts.
uint8_t vertical_mode
Definition: sim_ap.c:32
int32_t stabilization_cmd[COMMANDS_NB]
Stabilization commands.
Definition: stabilization.c:32
General stabilization interface for rotorcrafts.
struct Int32Quat stab_att_sp_quat
with INT32_QUAT_FRAC
int32_t transition_theta_offset
float stabilization_attitude_get_heading_f(void)
Read an attitude setpoint from the RC.
Rotorcraft attitude reference generation.
API to get/set the generic vehicle states.
static const struct usb_device_descriptor dev
Definition: usb_ser_hw.c:74
Architecture independent timing functions.
static float get_sys_time_float(void)
Get the time in seconds since startup.
Definition: sys_time.h:138
struct target_t target
Definition: target_pos.c:64
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.
Definition: telemetry.c:51
Periodic telemetry system header (includes downlink utility and generated code).
#define DefaultPeriodic
Set default periodic telemetry.
Definition: telemetry.h:66
int int32_t
Typedef defining 32 bit int type.
Definition: vl53l1_types.h:83
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.
Definition: vl53l1_types.h:98
signed char int8_t
Typedef defining 8 bit char type.
Definition: vl53l1_types.h:103
float heading
Definition: wedgebug.c:258