Paparazzi UAS  v5.12_stable-4-g9b43e9b
Paparazzi is a free software Unmanned Aircraft System.
 All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
guidance_indi.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 "subsystems/ins/ins_int.h"
34 #include "state.h"
35 #include "subsystems/imu.h"
40 #include "mcu_periph/sys_time.h"
41 #include "autopilot.h"
44 #include "stdio.h"
46 #include "subsystems/abi.h"
47 
48 // The acceleration reference is calculated with these gains. If you use GPS,
49 // they are probably limited by the update rate of your GPS. The default
50 // values are tuned for 4 Hz GPS updates. If you have high speed position updates, the
51 // gains can be higher, depending on the speed of the inner loop.
52 #ifdef GUIDANCE_INDI_POS_GAIN
53 float guidance_indi_pos_gain = GUIDANCE_INDI_POS_GAIN;
54 #else
56 #endif
57 
58 #ifdef GUIDANCE_INDI_SPEED_GAIN
59 float guidance_indi_speed_gain = GUIDANCE_INDI_SPEED_GAIN;
60 #else
62 #endif
63 
64 struct FloatVect3 sp_accel = {0.0,0.0,0.0};
65 #ifdef GUIDANCE_INDI_SPECIFIC_FORCE_GAIN
66 float thrust_in_specific_force_gain = GUIDANCE_INDI_SPECIFIC_FORCE_GAIN;
67 static void guidance_indi_filter_thrust(void);
68 
69 #ifndef GUIDANCE_INDI_THRUST_DYNAMICS
70 #ifndef STABILIZATION_INDI_ACT_DYN_P
71 #error "You need to define GUIDANCE_INDI_THRUST_DYNAMICS to be able to use indi vertical control"
72 #else // assume that the same actuators are used for thrust as for roll (e.g. quadrotor)
73 #define GUIDANCE_INDI_THRUST_DYNAMICS STABILIZATION_INDI_ACT_DYN_P
74 #endif
75 #endif //GUIDANCE_INDI_THRUST_DYNAMICS
76 
77 #endif //GUIDANCE_INDI_SPECIFIC_FORCE_GAIN
78 
79 #ifndef GUIDANCE_INDI_FILTER_CUTOFF
80 #ifdef STABILIZATION_INDI_FILT_CUTOFF
81 #define GUIDANCE_INDI_FILTER_CUTOFF STABILIZATION_INDI_FILT_CUTOFF
82 #else
83 #define GUIDANCE_INDI_FILTER_CUTOFF 3.0
84 #endif
85 #endif
86 
87 float thrust_act = 0;
92 
93 struct FloatMat33 Ga;
96 
98 
100 float thrust_in;
101 
102 static void guidance_indi_propagate_filters(void);
103 static void guidance_indi_calcG(struct FloatMat33 *Gmat);
104 
110  thrust_in = stabilization_cmd[COMMAND_THRUST];
112 
113  float tau = 1.0/(2.0*M_PI*filter_cutoff);
114  float sample_time = 1.0/PERIODIC_FREQUENCY;
115  for(int8_t i=0; i<3; i++) {
116  init_butterworth_2_low_pass(&filt_accel_ned[i], tau, sample_time, 0.0);
117  }
118  init_butterworth_2_low_pass(&roll_filt, tau, sample_time, stateGetNedToBodyEulers_f()->phi);
119  init_butterworth_2_low_pass(&pitch_filt, tau, sample_time, stateGetNedToBodyEulers_f()->theta);
120  init_butterworth_2_low_pass(&thrust_filt, tau, sample_time, thrust_in);
121 }
122 
129 void guidance_indi_run(bool in_flight, float heading_sp) {
130 
131  //filter accel to get rid of noise and filter attitude to synchronize with accel
133 
134  //Linear controller to find the acceleration setpoint from position and velocity
135  float pos_x_err = POS_FLOAT_OF_BFP(guidance_h.ref.pos.x) - stateGetPositionNed_f()->x;
136  float pos_y_err = POS_FLOAT_OF_BFP(guidance_h.ref.pos.y) - stateGetPositionNed_f()->y;
137  float pos_z_err = POS_FLOAT_OF_BFP(guidance_v_z_ref - stateGetPositionNed_i()->z);
138 
139  float speed_sp_x = pos_x_err * guidance_indi_pos_gain;
140  float speed_sp_y = pos_y_err * guidance_indi_pos_gain;
141  float speed_sp_z = pos_z_err * guidance_indi_pos_gain;
142 
143  sp_accel.x = (speed_sp_x - stateGetSpeedNed_f()->x) * guidance_indi_speed_gain;
144  sp_accel.y = (speed_sp_y - stateGetSpeedNed_f()->y) * guidance_indi_speed_gain;
145  sp_accel.z = (speed_sp_z - stateGetSpeedNed_f()->z) * guidance_indi_speed_gain;
146 
147 #if GUIDANCE_INDI_RC_DEBUG
148 #warning "GUIDANCE_INDI_RC_DEBUG lets you control the accelerations via RC, but disables autonomous flight!"
149  //for rc control horizontal, rotate from body axes to NED
150  float psi = stateGetNedToBodyEulers_f()->psi;
151  float rc_x = -(radio_control.values[RADIO_PITCH]/9600.0)*8.0;
152  float rc_y = (radio_control.values[RADIO_ROLL]/9600.0)*8.0;
153  sp_accel.x = cosf(psi) * rc_x - sinf(psi) * rc_y;
154  sp_accel.y = sinf(psi) * rc_x + cosf(psi) * rc_y;
155 
156  //for rc vertical control
157  sp_accel.z = -(radio_control.values[RADIO_THROTTLE]-4500)*8.0/9600.0;
158 #endif
159 
160  //Calculate matrix of partial derivatives
162  //Invert this matrix
163  MAT33_INV(Ga_inv, Ga);
164 
165  struct FloatVect3 a_diff = { sp_accel.x - filt_accel_ned[0].o[0], sp_accel.y -filt_accel_ned[1].o[0], sp_accel.z -filt_accel_ned[2].o[0]};
166 
167  //Bound the acceleration error so that the linearization still holds
168  Bound(a_diff.x, -6.0, 6.0);
169  Bound(a_diff.y, -6.0, 6.0);
170  Bound(a_diff.z, -9.0, 9.0);
171 
172  //If the thrust to specific force ratio has been defined, include vertical control
173  //else ignore the vertical acceleration error
174 #ifndef GUIDANCE_INDI_SPECIFIC_FORCE_GAIN
175 #ifndef STABILIZATION_ATTITUDE_INDI_FULL
176  a_diff.z = 0.0;
177 #endif
178 #endif
179 
180  //Calculate roll,pitch and thrust command
181  MAT33_VECT3_MUL(euler_cmd, Ga_inv, a_diff);
182 
183  AbiSendMsgTHRUST(THRUST_INCREMENT_ID, euler_cmd.z);
184 
185  guidance_euler_cmd.phi = roll_filt.o[0] + euler_cmd.x;
186  guidance_euler_cmd.theta = pitch_filt.o[0] + euler_cmd.y;
187  //zero psi command, because a roll/pitch quat will be constructed later
189 
190 #ifdef GUIDANCE_INDI_SPECIFIC_FORCE_GAIN
191  guidance_indi_filter_thrust();
192 
193  //Add the increment in specific force * specific_force_to_thrust_gain to the filtered thrust
194  thrust_in = thrust_filt.o[0] + euler_cmd.z*thrust_in_specific_force_gain;
195  Bound(thrust_in, 0, 9600);
196 
197 #if GUIDANCE_INDI_RC_DEBUG
199  thrust_in = 0;
200  }
201 #endif
202 
203  //Overwrite the thrust command from guidance_v
204  stabilization_cmd[COMMAND_THRUST] = thrust_in;
205 #endif
206 
207  //Bound euler angles to prevent flipping
210 
211  //set the quat setpoint with the calculated roll and pitch
213 }
214 
215 #ifdef GUIDANCE_INDI_SPECIFIC_FORCE_GAIN
216 
219 void guidance_indi_filter_thrust(void)
220 {
221  // Actuator dynamics
222  thrust_act = thrust_act + GUIDANCE_INDI_THRUST_DYNAMICS * (thrust_in - thrust_act);
223 
224  // same filter as for the acceleration
226 }
227 #endif
228 
235  struct NedCoor_f *accel = stateGetAccelNed_f();
236  update_butterworth_2_low_pass(&filt_accel_ned[0], accel->x);
237  update_butterworth_2_low_pass(&filt_accel_ned[1], accel->y);
238  update_butterworth_2_low_pass(&filt_accel_ned[2], accel->z);
239 
242 }
243 
250 void guidance_indi_calcG(struct FloatMat33 *Gmat) {
251 
252  struct FloatEulers *euler = stateGetNedToBodyEulers_f();
253 
254  float sphi = sinf(euler->phi);
255  float cphi = cosf(euler->phi);
256  float stheta = sinf(euler->theta);
257  float ctheta = cosf(euler->theta);
258  float spsi = sinf(euler->psi);
259  float cpsi = cosf(euler->psi);
260  //minus gravity is a guesstimate of the thrust force, thrust measurement would be better
261  float T = -9.81;
262 
263  RMAT_ELMT(*Gmat, 0, 0) = (cphi*spsi - sphi*cpsi*stheta)*T;
264  RMAT_ELMT(*Gmat, 1, 0) = (-sphi*spsi*stheta - cpsi*cphi)*T;
265  RMAT_ELMT(*Gmat, 2, 0) = -ctheta*sphi*T;
266  RMAT_ELMT(*Gmat, 0, 1) = (cphi*cpsi*ctheta)*T;
267  RMAT_ELMT(*Gmat, 1, 1) = (cphi*spsi*ctheta)*T;
268  RMAT_ELMT(*Gmat, 2, 1) = -stheta*cphi*T;
269  RMAT_ELMT(*Gmat, 0, 2) = sphi*spsi + cphi*cpsi*stheta;
270  RMAT_ELMT(*Gmat, 1, 2) = cphi*spsi*stheta - cpsi*sphi;
271  RMAT_ELMT(*Gmat, 2, 2) = cphi*ctheta;
272 }
273 
281 void stabilization_attitude_set_setpoint_rp_quat_f(struct FloatEulers* indi_rp_cmd, bool in_flight, float heading)
282 {
283  struct FloatQuat q_rp_cmd;
284  //this is a quaternion without yaw! add the desired yaw before you use it!
285  float_quat_of_eulers(&q_rp_cmd, indi_rp_cmd);
286 
287  /* get current heading */
288  const struct FloatVect3 zaxis = {0., 0., 1.};
289  struct FloatQuat q_yaw;
290 
291  float_quat_of_axis_angle(&q_yaw, &zaxis, stateGetNedToBodyEulers_f()->psi);
292 
293  /* roll/pitch commands applied to to current heading */
294  struct FloatQuat q_rp_sp;
295  float_quat_comp(&q_rp_sp, &q_yaw, &q_rp_cmd);
296  float_quat_normalize(&q_rp_sp);
297 
298  struct FloatQuat q_sp;
299 
300  if (in_flight) {
301  /* get current heading setpoint */
302  struct FloatQuat q_yaw_sp;
303  float_quat_of_axis_angle(&q_yaw_sp, &zaxis, heading);
304 
305 
306  /* rotation between current yaw and yaw setpoint */
307  struct FloatQuat q_yaw_diff;
308  float_quat_comp_inv(&q_yaw_diff, &q_yaw_sp, &q_yaw);
309 
310  /* compute final setpoint with yaw */
311  float_quat_comp_norm_shortest(&q_sp, &q_rp_sp, &q_yaw_diff);
312  } else {
313  QUAT_COPY(q_sp, q_rp_sp);
314  }
315 
317 }
void guidance_indi_enter(void)
Call upon entering indi guidance.
static float update_butterworth_2_low_pass(Butterworth2LowPass *filter, float value)
Update second order Butterworth low pass filter state with a new value.
void float_quat_comp_inv(struct FloatQuat *a2b, struct FloatQuat *a2c, struct FloatQuat *b2c)
Composition (multiplication) of two quaternions.
void float_quat_of_eulers(struct FloatQuat *q, struct FloatEulers *e)
Quaternion from Euler angles.
static void init_butterworth_2_low_pass(Butterworth2LowPass *filter, float tau, float sample_time, float value)
Init a second order Butterworth filter.
float y
in meters
#define GUIDANCE_H_MAX_BANK
Definition: guidance_h.c:66
float phi
in radians
struct FloatMat33 Ga
Definition: guidance_indi.c:93
#define RADIO_ROLL
Definition: spektrum_arch.h:43
static struct FloatEulers * stateGetNedToBodyEulers_f(void)
Get vehicle body attitude euler angles (float).
Definition: state.h:1143
void float_quat_comp(struct FloatQuat *a2c, struct FloatQuat *a2b, struct FloatQuat *b2c)
Composition (multiplication) of two quaternions.
General attitude stabilization interface for rotorcrafts.
struct FloatVect3 sp_accel
Definition: guidance_indi.c:64
Simple first order low pass filter with bilinear transform.
Main include for ABI (AirBorneInterface).
float thrust_act
Definition: guidance_indi.c:87
float psi
in radians
Vertical guidance for rotorcrafts.
struct HorizontalGuidanceReference ref
reference calculated from setpoints
Definition: guidance_h.h:101
pprz_t values[RADIO_CONTROL_NB_CHANNEL]
Definition: radio_control.h:58
#define GUIDANCE_INDI_FILTER_CUTOFF
Definition: guidance_indi.c:83
Butterworth2LowPass filt_accel_ned[3]
Definition: guidance_indi.c:88
struct Int32Quat stab_att_sp_quat
with INT32_QUAT_FRAC
euler angles
float z
in meters
float o[2]
output history
Roation quaternion.
#define QUAT_COPY(_qo, _qi)
Definition: pprz_algebra.h:543
float theta
in radians
Butterworth2LowPass pitch_filt
Definition: guidance_indi.c:90
float filter_cutoff
Definition: guidance_indi.c:97
static float heading
Definition: ahrs_infrared.c:45
Some helper functions to check RC sticks.
static void guidance_indi_calcG(struct FloatMat33 *Gmat)
vector in North East Down coordinates Units: meters
static struct NedCoor_f * stateGetSpeedNed_f(void)
Get ground speed in local NED coordinates (float).
Definition: state.h:908
void guidance_indi_run(bool in_flight, float heading_sp)
Architecture independent timing functions.
float guidance_indi_pos_gain
Definition: guidance_indi.c:55
#define RADIO_PITCH
Definition: spektrum_arch.h:44
static struct NedCoor_f * stateGetAccelNed_f(void)
Get acceleration in NED coordinates (float).
Definition: state.h:1038
struct FloatMat33 Ga_inv
Definition: guidance_indi.c:94
#define QUAT_BFP_OF_REAL(_qi, _qf)
Definition: pprz_algebra.h:696
static void float_quat_normalize(struct FloatQuat *q)
struct RadioControl radio_control
Definition: radio_control.c:30
struct HorizontalGuidance guidance_h
Definition: guidance_h.c:80
int32_t guidance_v_z_ref
altitude reference in meters.
Definition: guidance_v.c:128
#define RADIO_THROTTLE
Definition: spektrum_arch.h:42
struct FloatEulers guidance_euler_cmd
Definition: guidance_indi.c:99
struct FloatVect3 euler_cmd
Definition: guidance_indi.c:95
Inertial Measurement Unit interface.
float guidance_indi_speed_gain
Definition: guidance_indi.c:61
void stabilization_attitude_set_setpoint_rp_quat_f(struct FloatEulers *indi_rp_cmd, bool in_flight, float heading)
#define THRUST_INCREMENT_ID
Core autopilot interface common to all firmwares.
#define MAT33_VECT3_MUL(_vout, _mat, _vin)
Definition: pprz_algebra.h:462
struct Int32Vect2 pos
with INT32_POS_FRAC
Definition: guidance_h.h:79
API to get/set the generic vehicle states.
Butterworth2LowPass thrust_filt
Definition: guidance_indi.c:91
#define RMAT_ELMT(_rm, _row, _col)
Definition: pprz_algebra.h:604
void float_quat_of_axis_angle(struct FloatQuat *q, const struct FloatVect3 *uv, float angle)
Quaternion from unit vector and angle.
void float_quat_comp_norm_shortest(struct FloatQuat *a2c, struct FloatQuat *a2b, struct FloatQuat *b2c)
Composition (multiplication) of two quaternions with normalization.
General stabilization interface for rotorcrafts.
static void guidance_indi_propagate_filters(void)
Low pass the accelerometer measurements to remove noise from vibrations.
int32_t stabilization_cmd[COMMANDS_NB]
Stabilization commands.
Definition: stabilization.c:28
#define POS_FLOAT_OF_BFP(_ai)
Second order low pass filter structure.
static struct NedCoor_i * stateGetPositionNed_i(void)
Get position in local NED coordinates (int).
Definition: state.h:665
Horizontal guidance for rotorcrafts.
signed char int8_t
Definition: types.h:15
#define MAT33_INV(_minv, _m)
Definition: pprz_algebra.h:488
Butterworth2LowPass roll_filt
Definition: guidance_indi.c:89
static struct NedCoor_f * stateGetPositionNed_f(void)
Get position in local NED coordinates (float).
Definition: state.h:710
float thrust_in
Rotorcraft attitude reference generation.
A guidance mode based on Incremental Nonlinear Dynamic Inversion Come to ICRA2016 to learn more! ...
float x
in meters
INS for rotorcrafts combining vertical and horizontal filters.