32 #include "stabilization/stabilization_attitude.h"
33 #include "generated/airframe.h"
34 #include "generated/flight_plan.h"
42 #if defined SITL && USE_NPS
48 #ifndef USE_INS_NAV_INIT
49 #define USE_INS_NAV_INIT TRUE
53 #ifndef INS_EKF2_MAX_REL_LENGTH_ERROR
54 #define INS_EKF2_MAX_REL_LENGTH_ERROR 0.2
58 #if INS_EKF2_OPTITRACK
59 #ifndef INS_EKF2_FUSION_MODE
60 #define INS_EKF2_FUSION_MODE (MASK_USE_EVPOS | MASK_USE_EVVEL | MASK_USE_EVYAW)
62 #ifndef INS_EKF2_VDIST_SENSOR_TYPE
63 #define INS_EKF2_VDIST_SENSOR_TYPE VDIST_SENSOR_EV
68 #ifndef INS_EKF2_FUSION_MODE
69 #define INS_EKF2_FUSION_MODE (MASK_USE_GPS)
74 #ifndef INS_EKF2_VDIST_SENSOR_TYPE
75 #define INS_EKF2_VDIST_SENSOR_TYPE VDIST_SENSOR_BARO
80 #ifndef INS_EKF2_GPS_CHECK_MASK
81 #define INS_EKF2_GPS_CHECK_MASK 21
86 #ifndef INS_EKF2_SONAR_MIN_RANGE
87 #define INS_EKF2_SONAR_MIN_RANGE 0.001
92 #ifndef INS_EKF2_SONAR_MAX_RANGE
93 #define INS_EKF2_SONAR_MAX_RANGE 4
98 #ifndef INS_EKF2_RANGE_MAIN_AGL
99 #define INS_EKF2_RANGE_MAIN_AGL 1
104 #ifndef INS_EKF2_BARO_ID
106 #define INS_EKF2_BARO_ID BARO_BOARD_SENDER_ID
108 #define INS_EKF2_BARO_ID ABI_BROADCAST
114 #ifndef INS_EKF2_TEMPERATURE_ID
115 #define INS_EKF2_TEMPERATURE_ID ABI_BROADCAST
120 #ifndef INS_EKF2_AGL_ID
121 #define INS_EKF2_AGL_ID ABI_BROADCAST
126 #ifndef INS_EKF2_GYRO_ID
127 #define INS_EKF2_GYRO_ID ABI_BROADCAST
132 #ifndef INS_EKF2_ACCEL_ID
133 #define INS_EKF2_ACCEL_ID ABI_BROADCAST
138 #ifndef INS_EKF2_MAG_ID
139 #define INS_EKF2_MAG_ID ABI_BROADCAST
144 #ifndef INS_EKF2_GPS_ID
145 #define INS_EKF2_GPS_ID GPS_MULTI_ID
150 #ifndef INS_EKF2_RELPOS_ID
151 #define INS_EKF2_RELPOS_ID ABI_BROADCAST
156 #ifndef INS_EKF2_OF_ID
157 #define INS_EKF2_OF_ID ABI_BROADCAST
162 #ifndef INS_EKF2_IMU_POS_X
163 #define INS_EKF2_IMU_POS_X 0
168 #ifndef INS_EKF2_IMU_POS_Y
169 #define INS_EKF2_IMU_POS_Y 0
174 #ifndef INS_EKF2_IMU_POS_Z
175 #define INS_EKF2_IMU_POS_Z 0
180 #ifndef INS_EKF2_GPS_POS_X
181 #define INS_EKF2_GPS_POS_X 0
186 #ifndef INS_EKF2_GPS_POS_Y
187 #define INS_EKF2_GPS_POS_Y 0
192 #ifndef INS_EKF2_GPS_POS_Z
193 #define INS_EKF2_GPS_POS_Z 0
198 #ifndef INS_EKF2_FLOW_SENSOR_DELAY
199 #define INS_EKF2_FLOW_SENSOR_DELAY 15
204 #ifndef INS_EKF2_MIN_FLOW_QUALITY
205 #define INS_EKF2_MIN_FLOW_QUALITY 100
210 #ifndef INS_EKF2_MAX_FLOW_RATE
211 #define INS_EKF2_MAX_FLOW_RATE 200
216 #ifndef INS_EKF2_FLOW_POS_X
217 #define INS_EKF2_FLOW_POS_X 0
222 #ifndef INS_EKF2_FLOW_POS_Y
223 #define INS_EKF2_FLOW_POS_Y 0
228 #ifndef INS_EKF2_FLOW_POS_Z
229 #define INS_EKF2_FLOW_POS_Z 0
234 #ifndef INS_EKF2_FLOW_NOISE
235 #define INS_EKF2_FLOW_NOISE 0.03
240 #ifndef INS_EKF2_FLOW_NOISE_QMIN
241 #define INS_EKF2_FLOW_NOISE_QMIN 0.05
246 #ifndef INS_EKF2_FLOW_INNOV_GATE
247 #define INS_EKF2_FLOW_INNOV_GATE 4
252 #ifndef INS_EKF2_EVP_NOISE
253 #define INS_EKF2_EVP_NOISE 0.02f
258 #ifndef INS_EKF2_EVV_NOISE
259 #define INS_EKF2_EVV_NOISE 0.1f
264 #ifndef INS_EKF2_EVA_NOISE
265 #define INS_EKF2_EVA_NOISE 0.05f
270 #ifndef INS_EKF2_GPS_V_NOISE
271 #define INS_EKF2_GPS_V_NOISE 0.3f
276 #ifndef INS_EKF2_GPS_P_NOISE
277 #define INS_EKF2_GPS_P_NOISE 0.5f
282 #ifndef INS_EKF2_BARO_NOISE
283 #define INS_EKF2_BARO_NOISE 3.5f
288 #ifndef INS_EKF2_RELHEADING_ERR
289 #define INS_EKF2_RELHEADING_ERR 0.2
292 #ifdef INS_EXT_VISION_ROTATION
328 #if PERIODIC_TELEMETRY
331 static void send_ins(
struct transport_tx *trans,
struct link_device *
dev)
336 const Vector3f pos_f{
ekf.getPosition()};
337 const Vector3f speed_f{
ekf.getVelocity()};
338 const Vector3f accel_f{
ekf.getVelocityDerivative()};
352 pprz_msg_send_INS(trans,
dev, AC_ID,
353 &pos.
x, &pos.
y, &pos.
z,
354 &speed.
x, &speed.
y, &speed.
z,
355 &accel.
x, &accel.
y, &accel.
z);
364 const Vector3f pos_f{
ekf.getPosition()};
365 const Vector3f speed_f{
ekf.getVelocity()};
366 const Vector3f accel_f{
ekf.getVelocityDerivative()};
374 pprz_msg_send_INS_Z(trans,
dev, AC_ID,
375 &baro_z, &
pos_z, &speed_z, &accel_z);
380 float qfe = 101325.0;
382 pprz_msg_send_INS_REF(trans,
dev, AC_ID,
390 uint16_t gps_check_status, soln_status;
391 uint16_t filter_fault_status =
ekf.fault_status().value;
392 uint32_t control_mode =
ekf.control_status().value;
393 ekf.get_gps_check_status(&gps_check_status);
394 ekf.get_ekf_soln_status(&soln_status);
397 float mag, vel, pos, hgt, tas, hagl, flow, beta, mag_decl;
398 uint8_t terrain_valid, dead_reckoning;
399 ekf.get_innovation_test_status(innov_test_status, mag, vel, pos, hgt, tas, hagl, beta);
401 ekf.get_mag_decl_deg(&mag_decl);
403 if (
ekf.isTerrainEstimateValid()) {
409 if (
ekf.inertial_dead_reckoning()) {
415 pprz_msg_send_INS_EKF2(trans,
dev, AC_ID,
416 &control_mode, &filter_fault_status, &gps_check_status, &soln_status,
417 &innov_test_status, &mag, &vel, &pos, &hgt, &tas, &hagl, &flow, &beta,
418 &mag_decl, &terrain_valid, &dead_reckoning);
424 Vector3f vibe =
ekf.getImuVibrationMetrics();
427 ekf.get_gps_drift_metrics(gps_drift, &gps_blocked);
428 gps_blocked_b = gps_blocked;
430 pprz_msg_send_INS_EKF2_EXT(trans,
dev, AC_ID,
431 &gps_drift[0], &gps_drift[1], &gps_drift[2], &gps_blocked_b,
432 &vibe(0), &vibe(1), &vibe(2));
438 filter_control_status_u control_mode =
ekf.control_status();
439 uint32_t filter_fault_status =
ekf.fault_status().value;
440 uint16_t filter_fault_status_16 = filter_fault_status;
444 if (control_mode.flags.tilt_align && control_mode.flags.yaw_align && (control_mode.flags.gps || control_mode.flags.ev_pos)) {
446 }
else if (control_mode.flags.tilt_align && control_mode.flags.yaw_align) {
453 if (filter_fault_status) {
457 pprz_msg_send_STATE_FILTER_STATUS(trans,
dev, AC_ID, &ahrs_ekf2_id, &mde, &filter_fault_status_16);
463 Vector2f wind =
ekf.getWindVelocity();
467 ekf.get_true_airspeed(&tas);
469 pprz_msg_send_WIND_INFO_RET(trans,
dev, AC_ID, &flags, &wind(1), &wind(0), &f_zero, &tas);
474 Vector3f accel_bias =
ekf.getAccelBias();
475 Vector3f gyro_bias =
ekf.getGyroBias();
476 Vector3f mag_bias =
ekf.getMagBias();
478 pprz_msg_send_AHRS_BIAS(trans,
dev, AC_ID, &accel_bias(0), &accel_bias(1), &accel_bias(2),
479 &gyro_bias(0), &gyro_bias(1), &gyro_bias(2), &mag_bias(0), &mag_bias(1), &mag_bias(2));
485 const Quatf att_q{
ekf.calculate_quaternion()};
493 pprz_msg_send_AHRS_QUAT_INT(trans,
dev, AC_ID,
495 <p_to_body_quat.
qi,
496 <p_to_body_quat.
qx,
497 <p_to_body_quat.
qy,
498 <p_to_body_quat.
qz,
512 float sample_temp_ev[11];
513 sample_temp_ev[0] = (float)
sample_ev.time_us;
524 pprz_msg_send_EXTERNAL_POSE_DOWN(trans,
dev, AC_ID,
535 &sample_temp_ev[10] );
607 if(
ekf.setEkfGlobalOrigin(NAV_LAT0*1e-7, NAV_LON0*1e-7, (NAV_ALT0)*1e-3))
610 llh_nav0.
lat = NAV_LAT0;
611 llh_nav0.
lon = NAV_LON0;
613 llh_nav0.
alt = NAV_ALT0 + NAV_MSL0;
626 #if PERIODIC_TELEMETRY
659 if (
ekf.setEkfGlobalOrigin(lla_pos.
lat*1e-7, lla_pos.
lon*1e-7,
gps.
hmsl*1e-3)) {
711 filter_control_status_u control_status =
ekf.control_status();
714 if (control_status.flags.tilt_align) {
716 const Vector3f pos_f{
ekf.getPosition()};
726 const Vector3f vel_f{
ekf.getVelocity()};
736 const Vector3f vel_deriv_f{
ekf.getVelocityDerivative()};
738 accel.
x = vel_deriv_f(0);
739 accel.
y = vel_deriv_f(1);
740 accel.
z = vel_deriv_f(2);
747 double ekf_origin_lat, ekf_origin_lon;
753 bool ekf_origin_valid =
ekf.getEkfGlobalOrigin(origin_time, ekf_origin_lat, ekf_origin_lon, ref_alt);
755 lla_ref.
lat = ekf_origin_lat * 1e7;
756 lla_ref.
lon = ekf_origin_lon * 1e7;
770 #if defined SITL && USE_NPS
794 if (DL_EXTERNAL_POSE_ac_id(buf) != AC_ID) {
return; }
797 sample_ev.pos(0) = DL_EXTERNAL_POSE_enu_y(buf);
798 sample_ev.pos(1) = DL_EXTERNAL_POSE_enu_x(buf);
799 sample_ev.pos(2) = -DL_EXTERNAL_POSE_enu_z(buf);
800 sample_ev.vel(0) = DL_EXTERNAL_POSE_enu_yd(buf);
801 sample_ev.vel(1) = DL_EXTERNAL_POSE_enu_xd(buf);
802 sample_ev.vel(2) = -DL_EXTERNAL_POSE_enu_zd(buf);
803 sample_ev.quat(0) = DL_EXTERNAL_POSE_body_qi(buf);
804 sample_ev.quat(1) = DL_EXTERNAL_POSE_body_qy(buf);
805 sample_ev.quat(2) = DL_EXTERNAL_POSE_body_qx(buf);
806 sample_ev.quat(3) = -DL_EXTERNAL_POSE_body_qz(buf);
808 #ifdef INS_EXT_VISION_ROTATION
822 sample_ev.vel_frame = velocity_frame_t::LOCAL_FRAME_FRD;
836 imuSample imu_sample = {};
837 imu_sample.time_us = stamp;
842 ekf.setIMUData(imu_sample);
844 if (
ekf.attitude_valid()) {
847 const Quatf att_q{
ekf.calculate_quaternion()};
848 ltp_to_body_quat.
qi = att_q(0);
849 ltp_to_body_quat.
qx = att_q(1);
850 ltp_to_body_quat.
qy = att_q(2);
851 ltp_to_body_quat.
qz = att_q(3);
857 float delta_q_reset[4];
859 ekf.get_quat_reset(delta_q_reset, &quat_reset_counter);
861 #ifndef NO_RESET_UPDATE_SETPOINT_HEADING
864 float psi = matrix::Eulerf(matrix::Quatf(delta_q_reset)).psi();
876 Vector3f gyro_bias{
ekf.getGyroBias()};
886 Vector3f accel_bias{
ekf.getAccelBias()};
904 sample.time_us = stamp;
908 ekf.set_air_density(rho);
912 ekf.setBaroData(sample);
925 sample.time_us = stamp;
926 sample.rng = distance;
929 ekf.setRangeData(sample);
969 sample.time_us = stamp;
978 sample.mag(0) = mag_gauss.
x;
979 sample.mag(1) = mag_gauss.
y;
980 sample.mag(2) = mag_gauss.
z;
982 ekf.setMagData(sample);
991 gps_message gps_msg = {};
992 gps_msg.time_usec = stamp;
994 gps_msg.lat = lla_pos.
lat;
995 gps_msg.lon = lla_pos.
lon;
996 gps_msg.alt = gps_s->
hmsl;
997 #if INS_EKF2_GPS_COURSE_YAW
998 gps_msg.yaw = wrap_pi((
float)gps_s->
course / 1e7);
999 gps_msg.yaw_offset = 0;
1000 #elif defined(INS_EKF2_GPS_YAW_OFFSET)
1002 gps_msg.yaw = wrap_pi(
ekf2.
rel_heading - RadOfDeg(INS_EKF2_GPS_YAW_OFFSET));
1009 gps_msg.yaw_offset = RadOfDeg(INS_EKF2_GPS_YAW_OFFSET);
1012 gps_msg.yaw_offset = NAN;
1014 gps_msg.fix_type = gps_s->
fix;
1015 gps_msg.eph = gps_s->
hacc / 100.0;
1016 gps_msg.epv = gps_s->
vacc / 100.0;
1017 gps_msg.sacc = gps_s->
sacc / 100.0;
1018 gps_msg.vel_m_s = gps_s->
gspeed / 100.0;
1020 gps_msg.vel_ned(0) = ned_vel.
x;
1021 gps_msg.vel_ned(1) = ned_vel.
y;
1022 gps_msg.vel_ned(2) = ned_vel.
z;
1024 gps_msg.nsats = gps_s->
num_sv;
1025 gps_msg.pdop = gps_s->
pdop;
1027 ekf.setGpsData(gps_msg);
1035 #ifdef INS_EKF2_RELHEADING_REF_ID
1038 #ifdef INS_EKF2_RELHEADING_DISTANCE
1055 int32_t flow_der_x __attribute__((unused)),
1056 int32_t flow_der_y __attribute__((unused)),
1058 float size_divergence __attribute__((unused)))
1061 sample.time_us = stamp;
1077 flowdata(0) = RadOfDeg(flow_y) * (1e-6 *
1079 flowdata(1) = - RadOfDeg(flow_x) * (1e-6 *
1082 sample.quality = quality;
1083 sample.flow_xy_rad =
1085 sample.gyro_xyz = Vector3f{NAN, NAN, NAN};
1088 ekf.setOpticalFlowData(sample);
Main include for ABI (AirBorneInterface).
#define ABI_BROADCAST
Broadcast address.
Event structure to store callbacks in a linked list.
#define AHRS_COMP_ID_EKF2
bool autopilot_in_flight(void)
get in_flight flag
Core autopilot interface common to all firmwares.
uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
static const float pos_z[]
struct NedCoor_f ned_vel_float_from_gps(struct GpsState *gps_s)
Get GPS ned velocity (float) Converted on the fly if not available.
struct GpsState gps
global GPS state
struct LlaCoor_i lla_int_from_gps(struct GpsState *gps_s)
Get GPS lla (integer) Converted on the fly if not available.
int32_t hmsl
height above mean sea level (MSL) in mm
float heading
Relative heading to the reference station in radians.
uint32_t sacc
speed accuracy in cm/s
int32_t course
GPS course over ground in rad*1e7, [0, 2*Pi]*1e7 (CW/north)
#define GPS_VALID_VEL_NED_BIT
uint32_t hacc
horizontal accuracy in cm
double distance
Relative distance to the reference station in meters.
uint16_t pdop
position dilution of precision scaled by 100
uint16_t gspeed
norm of 2d ground speed in cm/s
uint8_t valid_fields
bitfield indicating valid fields (GPS_VALID_x_BIT)
uint32_t vacc
vertical accuracy in cm
uint16_t reference_id
Reference station identification.
uint8_t num_sv
number of sat in fix
data structure for GPS information
void float_quat_comp(struct FloatQuat *a2c, struct FloatQuat *a2b, struct FloatQuat *b2c)
Composition (multiplication) of two quaternions.
#define MAGS_FLOAT_OF_BFP(_ef, _ei)
#define RATES_COPY(_a, _b)
#define VECT3_COPY(_a, _b)
#define QUAT1_BFP_OF_REAL(_qf)
#define ACCEL_BFP_OF_REAL(_af)
#define POS_BFP_OF_REAL(_af)
#define SPEED_BFP_OF_REAL(_af)
int32_t lat
in degrees*1e7
int32_t hmsl
Height above mean sea level in mm.
int32_t alt
in millimeters above WGS84 reference ellipsoid
struct LlaCoor_i lla
Reference point in lla.
struct EcefCoor_i ecef
Reference point in ecef.
int32_t lon
in degrees*1e7
void ltp_def_from_lla_i(struct LtpDef_i *def, struct LlaCoor_i *lla)
vector in Latitude, Longitude and Altitude
vector in North East Down coordinates
static int32_t wgs84_ellipsoid_to_geoid_i(int32_t lat, int32_t lon)
Get WGS84 ellipsoid/geoid separation.
static float pprz_isa_density_of_pressure(float pressure, float temp)
Get the air density (rho) from a given pressure and temperature.
static float pprz_isa_height_of_pressure_full(float pressure, float ref_p)
Get relative altitude from pressure (using full equation).
static void stateSetAccelNed_f(uint16_t id, struct NedCoor_f *ned_accel)
Set acceleration in NED coordinates (float).
static void stateSetAccelBody_i(uint16_t id, struct Int32Vect3 *body_accel)
Set acceleration in Body coordinates (int).
static struct Int32Quat * stateGetNedToBodyQuat_i(void)
Get vehicle body attitude quaternion (int).
static void stateSetNedToBodyQuat_f(uint16_t id, struct FloatQuat *ned_to_body_quat)
Set vehicle body attitude from quaternion (float).
static void stateSetPositionNed_f(uint16_t id, struct NedCoor_f *ned_pos)
Set position from local NED coordinates (float).
static void stateSetLocalOrigin_i(uint16_t id, struct LtpDef_i *ltp_def)
Set the local (flat earth) coordinate frame origin (int).
struct LlaCoor_i stateGetLlaOrigin_i(void)
Get the LLA position of the frame origin (int)
static void stateSetBodyRates_f(uint16_t id, struct FloatRates *body_rate)
Set vehicle body angular rate (float).
static void stateSetSpeedNed_f(uint16_t id, struct NedCoor_f *ned_speed)
Set ground speed in local NED coordinates (float).
#define INS_RESET_VERTICAL_REF
#define INS_RESET_REF
flags for INS reset
static void reset_vertical_ref(void)
static void relpos_cb(uint8_t sender_id, uint32_t stamp, struct RelPosNED *relpos)
static abi_event optical_flow_ev
static void gps_cb(uint8_t sender_id, uint32_t stamp, struct GpsState *gps_s)
#define INS_EKF2_EVV_NOISE
void ins_ekf2_update(void)
#define INS_EKF2_IMU_POS_Z
static void reset_cb(uint8_t sender_id, uint8_t flag)
static void send_ins(struct transport_tx *trans, struct link_device *dev)
#define INS_EKF2_GPS_POS_Y
static void send_ins_ekf2(struct transport_tx *trans, struct link_device *dev)
void ins_ekf2_remove_gps(int32_t mode)
static void send_ins_ekf2_ext(struct transport_tx *trans, struct link_device *dev)
static abi_event temperature_ev
static void optical_flow_cb(uint8_t sender_id, uint32_t stamp, int32_t flow_x, int32_t flow_y, int32_t flow_der_x, int32_t flow_der_y, float quality, float size_divergence)
#define INS_EKF2_TEMPERATURE_ID
default temperature sensor to use in INS
#define INS_EKF2_RELHEADING_ERR
#define INS_EKF2_VDIST_SENSOR_TYPE
The EKF2 primary vertical distance sensor type.
static void reset_ref(void)
#define INS_EKF2_RELPOS_ID
static void mag_cb(uint8_t sender_id, uint32_t stamp, struct Int32Vect3 *mag)
static void accel_int_cb(uint8_t sender_id, uint32_t stamp, struct FloatVect3 *delta_accel, uint16_t dt)
#define INS_EKF2_FUSION_MODE
Special configuration for Optitrack.
static abi_event reset_ev
#define INS_EKF2_GPS_CHECK_MASK
The EKF2 GPS checks before initialization.
#define INS_EKF2_RANGE_MAIN_AGL
If enabled uses radar sensor as primary AGL source, if possible.
#define INS_EKF2_MAX_FLOW_RATE
#define INS_EKF2_GPS_POS_Z
static abi_event gyro_int_ev
static abi_event relpos_ev
#define INS_EKF2_EVA_NOISE
#define INS_EKF2_BARO_NOISE
#define INS_EKF2_ACCEL_ID
static void send_ins_ref(struct transport_tx *trans, struct link_device *dev)
static void temperature_cb(uint8_t sender_id, float temp)
#define INS_EKF2_FLOW_POS_Y
static void agl_cb(uint8_t sender_id, uint32_t stamp, float distance)
static void send_ins_z(struct transport_tx *trans, struct link_device *dev)
static parameters * ekf_params
The EKF parameters.
static void send_filter_status(struct transport_tx *trans, struct link_device *dev)
#define INS_EKF2_FLOW_INNOV_GATE
#define INS_EKF2_FLOW_NOISE
#define INS_EKF2_EVP_NOISE
static void baro_cb(uint8_t sender_id, uint32_t stamp, float pressure)
void ins_ekf2_change_param(int32_t unk)
static void send_wind_info_ret(struct transport_tx *trans, struct link_device *dev)
#define INS_EKF2_MIN_FLOW_QUALITY
#define INS_EKF2_GPS_V_NOISE
static Ekf ekf
EKF class itself.
struct ekf2_t ekf2
Local EKF2 status structure.
#define INS_EKF2_FLOW_SENSOR_DELAY
void ins_ekf2_parse_EXTERNAL_POSE(uint8_t *buf)
void ins_ekf2_parse_EXTERNAL_POSE_SMALL(uint8_t *buf)
#define INS_EKF2_IMU_POS_X
#define INS_EKF2_GPS_P_NOISE
static void send_ahrs_quat(struct transport_tx *trans, struct link_device *dev)
#define INS_EKF2_AGL_ID
default AGL sensor to use in INS
static void ins_ekf2_publish_attitude(uint32_t stamp)
Publish the attitude and get the new state Directly called after a succeslfull gyro+accel reading.
static void gyro_int_cb(uint8_t sender_id, uint32_t stamp, struct FloatRates *delta_gyro, uint16_t dt)
#define INS_EKF2_SONAR_MIN_RANGE
Default AGL sensor minimum range.
#define INS_EKF2_FLOW_NOISE_QMIN
#define INS_EKF2_IMU_POS_Y
static abi_event accel_int_ev
#define INS_EKF2_FLOW_POS_Z
static struct extVisionSample sample_ev
External vision sample.
#define INS_EKF2_BARO_ID
default barometer to use in INS
static void send_external_pose_down(struct transport_tx *trans, struct link_device *dev)
#define INS_EKF2_SONAR_MAX_RANGE
Default AGL sensor maximum range.
#define INS_EKF2_GPS_POS_X
#define INS_EKF2_FLOW_POS_X
static void send_ahrs_bias(struct transport_tx *trans, struct link_device *dev)
INS based in the EKF2 of PX4.
bool accel_valid
If we received a acceleration measurement.
bool rel_heading_valid
If we received a valid relative heading.
bool got_imu_data
If we received valid IMU data (any sensor)
bool gyro_valid
If we received a gyroscope measurement.
uint32_t accel_dt
Accelerometer delta timestamp between abi messages (us)
uint32_t gyro_dt
Gyroscope delta timestamp between abi messages (us)
struct LtpDef_i ltp_def
Latest LTP definition from the quat_reset_counter EKF2.
uint32_t flow_stamp
Optic flow last abi message timestamp.
float rel_heading
Relative heading from RTK gps (rad)
float temp
Latest temperature measurement in degrees celcius.
struct FloatVect3 delta_accel
Last accelerometer measurements.
uint64_t ltp_stamp
Last LTP change timestamp from the EKF2.
float qnh
QNH value in hPa.
uint8_t quat_reset_counter
Amount of quaternion resets from the EKF2.
struct FloatRates delta_gyro
Last gyroscope measurements.
void waypoints_localize_all(void)
update local ENU coordinates of global waypoints
void sim_overwrite_ins(void)
PRINT_CONFIG_VAR(ONELOOP_ANDI_FILT_CUTOFF)
vector in North East Down coordinates Units: meters
Paparazzi atmospheric pressure conversion utilities.
struct HorizontalGuidance guidance_h
struct HorizontalGuidanceRCInput rc_sp
remote control setpoint
struct HorizontalGuidanceSetpoint sp
setpoints
struct RotorcraftNavigation nav
float heading
heading setpoint (in radians)
void stabilization_attitude_enter(void)
Attitude control enter function.
static uint8_t mode
mode holds the current sonar mode mode = 0 used at high altitude, uses 16 wave patterns mode = 1 used...
static const struct usb_device_descriptor dev
Architecture independent timing functions.
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.
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
int int32_t
Typedef defining 32 bit int type.
unsigned int uint32_t
Typedef defining 32 bit unsigned int type.
unsigned long long uint64_t
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.