30 #include "generated/airframe.h"
54 #ifndef GUIDANCE_INDI_SPEED_GAIN
55 #define GUIDANCE_INDI_SPEED_GAIN 1.8
56 #define GUIDANCE_INDI_SPEED_GAINZ 1.8
59 #ifndef GUIDANCE_INDI_POS_GAIN
60 #define GUIDANCE_INDI_POS_GAIN 0.5
61 #define GUIDANCE_INDI_POS_GAINZ 0.5
64 #ifndef GUIDANCE_INDI_MIN_PITCH
65 #define GUIDANCE_INDI_MIN_PITCH -120
66 #define GUIDANCE_INDI_MAX_PITCH 25
69 #ifndef GUIDANCE_INDI_LIFTD_ASQ
70 #define GUIDANCE_INDI_LIFTD_ASQ 0.20
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)
89 .heading_bank_gain = GUIDANCE_INDI_HEADING_BANK_GAIN,
95 #ifndef GUIDANCE_INDI_MAX_AIRSPEED
96 #error "You must have an airspeed sensor to use this guidance"
102 #ifndef GUIDANCE_INDI_ZERO_AIRSPEED
103 #define GUIDANCE_INDI_ZERO_AIRSPEED FALSE
107 #ifndef GUIDANCE_INDI_NAV_SPEED_MARGIN
108 #define GUIDANCE_INDI_NAV_SPEED_MARGIN 10.0
110 #define NAV_MAX_SPEED (GUIDANCE_INDI_MAX_AIRSPEED + GUIDANCE_INDI_NAV_SPEED_MARGIN)
113 #ifndef MAX_DECELERATION
114 #define MAX_DECELERATION 1.
118 #ifndef TURN_AIRSPEED_TH
119 #define TURN_AIRSPEED_TH 10.0
126 #ifdef GUIDANCE_INDI_SPECIFIC_FORCE_GAIN
128 static void guidance_indi_filter_thrust(
void);
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"
134 #define GUIDANCE_INDI_THRUST_DYNAMICS STABILIZATION_INDI_ACT_DYN_P
140 #ifndef GUIDANCE_INDI_FILTER_CUTOFF
141 #ifdef STABILIZATION_INDI_FILT_CUTOFF
142 #define GUIDANCE_INDI_FILTER_CUTOFF STABILIZATION_INDI_FILT_CUTOFF
144 #define GUIDANCE_INDI_FILTER_CUTOFF 3.0
148 #ifdef GUIDANCE_INDI_LINE_GAIN
182 #ifndef GUIDANCE_INDI_VEL_SP_ID
183 #define GUIDANCE_INDI_VEL_SP_ID ABI_BROADCAST
197 #if PERIODIC_TELEMETRY
201 pprz_msg_send_GUIDANCE_INDI_HYBRID(trans,
dev, AC_ID,
226 float sample_time = 1.0/PERIODIC_FREQUENCY;
227 for(
int8_t i=0; i<3; i++) {
235 #if PERIODIC_TELEMETRY
249 float sample_time = 1.0 / PERIODIC_FREQUENCY;
250 for (
int8_t i = 0; i < 3; i++) {
315 struct FloatVect2 airspeed_v = {cos(psi)*airspeed, sin(psi)*airspeed};
317 VECT2_DIFF(windspeed, *groundspeed, airspeed_v);
327 float groundspeed_factor = 0.0;
335 float dv = bv * bv - 4.0 * av * cv;
341 float d_sqrt = sqrtf(dv);
343 groundspeed_factor = (-bv + d_sqrt) / (2.0 * av);
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;
375 if(airspeed > 10.0) {
378 float speed_increment = speed_sp_b_x - groundspeed_x;
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;
401 #if GUIDANCE_INDI_RC_DEBUG
402 #warning "GUIDANCE_INDI_RC_DEBUG lets you control the accelerations via RC, but disables autonomous flight!"
407 sp_accel.
x = cosf(psi) * rc_x - sinf(psi) * rc_y;
408 sp_accel.
y = sinf(psi) * rc_x + cosf(psi) * rc_y;
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);
436 #ifndef GUIDANCE_INDI_SPECIFIC_FORCE_GAIN
437 #ifndef STABILIZATION_ATTITUDE_INDI_FULL
450 const float max_phi = RadOfDeg(60.0);
451 float airspeed_turn = airspeed;
453 Bound(airspeed_turn,10.0,30.0);
469 if (fabs(coordinated_turn_roll) < max_phi) {
470 omega = 9.81 / airspeed_turn * tanf(coordinated_turn_roll);
472 omega = 9.81 / airspeed_turn * 1.72305 * ((coordinated_turn_roll > 0.0) - (coordinated_turn_roll < 0.0));
475 #ifdef FWD_SIDESLIP_GAIN
482 #ifndef KNIFE_EDGE_TEST
486 *heading_sp += omega / PERIODIC_FREQUENCY;
489 #ifdef STABILIZATION_ATTITUDE_SP_PSI_DELTA_LIMIT
490 float delta_limit = STABILIZATION_ATTITUDE_SP_PSI_DELTA_LIMIT;
493 float delta_psi = *heading_sp -
heading;
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;
507 #ifdef GUIDANCE_INDI_SPECIFIC_FORCE_GAIN
508 guidance_indi_filter_thrust();
512 Bound(
thrust_in, GUIDANCE_INDI_MIN_THROTTLE, 9600);
514 #if GUIDANCE_INDI_RC_DEBUG
531 #ifdef GUIDANCE_INDI_SPECIFIC_FORCE_GAIN
535 void guidance_indi_filter_thrust(
void)
583 #ifndef GUIDANCE_INDI_PITCH_EFF_SCALING
584 #define GUIDANCE_INDI_PITCH_EFF_SCALING 1.0
589 Bound(pitch_lift,-M_PI_2,0);
590 float lift = sinf(pitch_lift)*9.81;
591 float T = cosf(pitch_lift)*-9.81;
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;
602 RMAT_ELMT(*Gmat, 0, 2) = stheta*cpsi + sphi*ctheta*spsi;
603 RMAT_ELMT(*Gmat, 1, 2) = stheta*spsi - sphi*ctheta*cpsi;
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;
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);
632 float ratio = (pitch_interp - middle_pitch)/(min_pitch - middle_pitch);
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};
687 desired_speed = dist_to_target * pos_gain;
693 if(length_line < 0.01) {
701 float length_normalv = length_line;
702 if(length_normalv < 0.01) {
703 length_normalv = 0.01;
707 float dist_to_line = (to_end_v.
x*normalv.x + to_end_v.
y*normalv.y)/length_normalv;
715 float dist_to_line_abs = fabs(dist_to_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;
727 if(length_direction < 0.01) {
728 length_direction = 0.01;
742 Bound(speed_sp_return.
z, -4.0, 5.0);
747 return speed_sp_return;
769 VECT3_SMUL(speed_sp_return, pos_error, pos_gain);
786 if(max_speed_decel2 < 0.0) {
787 max_speed_decel2 = fabs(max_speed_decel2);
789 float max_speed_decel = sqrtf(max_speed_decel2);
798 Bound(speed_sp_return.
z, -4.0, 5.0);
803 return speed_sp_return;
Main include for ABI (AirBorneInterface).
Event structure to store callbacks in a linked list.
#define THRUST_INCREMENT_ID
struct pprz_autopilot autopilot
Global autopilot structure.
Core autopilot interface common to all firmwares.
uint8_t mode
current autopilot mode
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)
#define VECT2_ADD(_a, _b)
#define VECT2_SMUL(_vo, _vi, _s)
#define VECT2_DIFF(_c, _a, _b)
#define MAT33_VECT3_MUL(_vout, _mat, _vin)
#define MAT33_INV(_minv, _m)
#define QUAT_BFP_OF_REAL(_qi, _qf)
#define VECT3_SMUL(_vo, _vi, _s)
#define VECT3_ASSIGN(_a, _x, _y, _z)
#define RMAT_ELMT(_rm, _row, _col)
#define VECT3_DIFF(_c, _a, _b)
#define VECT2_ASSIGN(_a, _x, _y)
#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 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).
static struct FloatEulers * stateGetNedToBodyEulers_f(void)
Get vehicle body attitude euler angles (float).
static struct FloatQuat * stateGetNedToBodyQuat_f(void)
Get vehicle body attitude quaternion (float).
static struct NedCoor_f * stateGetPositionNed_f(void)
Get position in local NED coordinates (float).
static struct NedCoor_i * stateGetPositionNed_i(void)
Get position in local NED coordinates (int).
static struct NedCoor_f * stateGetSpeedNed_f(void)
Get ground speed in local NED coordinates (float).
static struct Int32Vect3 * stateGetAccelBody_i(void)
Get acceleration in Body coordinates (int).
static float stateGetAirspeed_f(void)
Get airspeed (float).
struct FloatVect3 speed_sp
float guidance_indi_specific_force_gain
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.
Butterworth2LowPass roll_filt
#define GUIDANCE_INDI_SPEED_GAINZ
struct guidance_indi_hybrid_params gih_params
struct FloatVect3 gi_speed_sp
float guidance_indi_max_bank
#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.
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.
#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
Butterworth2LowPass filt_accel_ned[3]
#define GUIDANCE_INDI_POS_GAINZ
float guidance_indi_max_airspeed
#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
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.
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.
#define HORIZONTAL_MODE_ROUTE
vector in North East Down coordinates Units: meters
struct RadioControl radio_control
Generic interface for radio control modules.
pprz_t values[RADIO_CONTROL_NB_CHANNEL]
#define RADIO_ROLL
Redefining RADIO_* Do not use with radio.h (ppm rc)
Some helper functions to check RC sticks.
int32_t transition_percentage
struct HorizontalGuidance guidance_h
#define GUIDANCE_H_MAX_BANK
Horizontal guidance for rotorcrafts.
struct Int32Vect2 pos
with INT32_POS_FRAC
struct HorizontalGuidanceReference ref
reference calculated from setpoints
int32_t guidance_v_z_ref
altitude reference in meters.
int32_t guidance_v_zd_sp
vertical speed setpoint in meter/s (input).
Vertical guidance for rotorcrafts.
#define GUIDANCE_V_MODE_NAV
int32_t nav_flight_altitude
struct FloatVect2 line_vect to_end_vect
struct EnuCoor_i navigation_target
int32_t nav_heading
with INT32_ANGLE_FRAC
Rotorcraft navigation functions.
#define VERTICAL_MODE_CLIMB
General attitude stabilization interface for rotorcrafts.
int32_t stabilization_cmd[COMMANDS_NB]
Stabilization commands.
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
Architecture independent timing functions.
static float get_sys_time_float(void)
Get the time in seconds since startup.
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.
Periodic telemetry system header (includes downlink utility and generated code).
#define DefaultPeriodic
Set default periodic telemetry.
int int32_t
Typedef defining 32 bit int type.
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.
signed char int8_t
Typedef defining 8 bit char type.