27#include "generated/airframe.h"
42#ifndef ROTWING_EFF_SCHED_IXX_BODY
43#error "NO ROTWING_EFF_SCHED_IXX_BODY defined"
46#ifndef ROTWING_EFF_SCHED_IYY_BODY
47#error "NO ROTWING_EFF_SCHED_IYY_BODY defined"
50#ifndef ROTWING_EFF_SCHED_IZZ
51#error "NO ROTWING_EFF_SCHED_IZZ defined"
54#ifndef ROTWING_EFF_SCHED_IXX_WING
55#error "NO ROTWING_EFF_SCHED_IXX_WING defined"
58#ifndef ROTWING_EFF_SCHED_IYY_WING
59#error "NO ROTWING_EFF_SCHED_IYY_WING defined"
62#ifndef ROTWING_EFF_SCHED_M
63#error "NO ROTWING_EFF_SCHED_M defined"
95#ifndef WING_ROTATION_CAN_ROTWING_ID
96#define WING_ROTATION_CAN_ROTWING_ID ABI_BROADCAST
113#include "generated/modules.h"
183 RW.
wing.
k0 = 0.336 + 0.0507 + 0.102;
393#ifdef INS_EXT_VISION_ROTATION
Main include for ABI (AirBorneInterface).
Event structure to store callbacks in a linked list.
void update_attitude(void)
float G2_RW[EFF_MAT_COLS_NB]
float G1_RW[EFF_MAT_ROWS_NB][EFF_MAT_COLS_NB]
struct FloatEulers eulers_zxy_RW_EFF
#define WING_ROTATION_CAN_ROTWING_ID
ABI binding wing position data.
float actuator_state_filt_vect[EFF_MAT_COLS_NB]
void eff_scheduling_rotwing_update_airspeed(void)
float EFF_MAT_RW[EFF_MAT_ROWS_NB][EFF_MAT_COLS_NB]
static Butterworth2LowPass skew_filt
void ele_pref_sched(void)
void eff_scheduling_rotwing_update_wing_angle(void)
static abi_event wing_position_ev
void eff_scheduling_rotwing_init(void)
void sum_EFF_MAT_RW(void)
Function that sums g1 and g2 to obtain the g1_g2 matrix.
void eff_scheduling_rotwing_periodic(void)
static void wing_position_cb(uint8_t sender_id UNUSED, struct act_feedback_t *pos_msg, uint8_t num_act)
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
void float_quat_of_eulers(struct FloatQuat *q, struct FloatEulers *e)
quat of euler roation 'ZYX'
static struct FloatQuat * stateGetNedToBodyQuat_f(void)
Get vehicle body attitude quaternion (float).
static float stateGetAirspeed_f(void)
Get airspeed (float).
Integrated Navigation System interface.
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.
Hardware independent API for actuators (servos, motor controllers).
PRINT_CONFIG_VAR(ONELOOP_ANDI_FILT_CUTOFF)
float actuator_state_1l[ANDI_NUM_ACT]
API to get/set the generic vehicle states.
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.