Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_DAL/LogStructure.h
Views: 1798
#pragma once12#include <AP_Logger/LogStructure.h>3#include <AP_Math/vector3.h>4#include <AP_Math/vector2.h>5#include <AP_Math/matrix3.h>6#include <AP_Math/quaternion.h>78#define LOG_IDS_FROM_DAL \9LOG_RFRH_MSG, \10LOG_RFRF_MSG, \11LOG_REV2_MSG, \12LOG_RSO2_MSG, \13LOG_RWA2_MSG, \14LOG_REV3_MSG, \15LOG_RSO3_MSG, \16LOG_RWA3_MSG, \17LOG_REY3_MSG, \18LOG_RFRN_MSG, \19LOG_RISH_MSG, \20LOG_RISI_MSG, \21LOG_RBRH_MSG, \22LOG_RBRI_MSG, \23LOG_RRNH_MSG, \24LOG_RRNI_MSG, \25LOG_RGPH_MSG, \26LOG_RGPI_MSG, \27LOG_RGPJ_MSG, \28LOG_RASH_MSG, \29LOG_RASI_MSG, \30LOG_RBCH_MSG, \31LOG_RBCI_MSG, \32LOG_RVOH_MSG, \33LOG_RMGH_MSG, \34LOG_RMGI_MSG, \35LOG_ROFH_MSG, \36LOG_REPH_MSG, \37LOG_RSLL_MSG, \38LOG_REVH_MSG, \39LOG_RWOH_MSG, \40LOG_RBOH_MSG4142// @LoggerMessage: RFRH43// @Description: Replay FRame Header44struct log_RFRH {45uint64_t time_us;46uint32_t time_flying_ms;47uint8_t _end;48};4950// @LoggerMessage: RFRF51// @Description: Replay FRame data - Finished frame52struct log_RFRF {53uint8_t frame_types;54uint8_t core_slow;55uint8_t _end;56};5758// @LoggerMessage: RFRN59// @Description: Replay FRame - aNother frame header60struct log_RFRN {61int32_t lat;62int32_t lng;63int32_t alt;64float EAS2TAS;65uint32_t available_memory;66Vector3f ahrs_trim;67uint8_t vehicle_class;68uint8_t ekf_type;69uint8_t armed:1;70uint8_t unused:1; // was get_compass_is_null71uint8_t fly_forward:1;72uint8_t ahrs_airspeed_sensor_enabled:1;73uint8_t opticalflow_enabled:1;74uint8_t wheelencoder_enabled:1;75uint8_t takeoff_expected:1;76uint8_t touchdown_expected:1;77uint8_t _end;78};7980// @LoggerMessage: RISH81// @Description: Replay Inertial Sensor header82struct log_RISH {83uint16_t loop_rate_hz;84uint8_t first_usable_gyro;85uint8_t first_usable_accel;86float loop_delta_t;87uint8_t accel_count;88uint8_t gyro_count;89uint8_t _end;90};9192// @LoggerMessage: RISI93// @Description: Replay Inertial Sensor instance data94struct log_RISI {95Vector3f delta_velocity;96Vector3f delta_angle;97float delta_velocity_dt;98float delta_angle_dt;99uint8_t use_accel:1;100uint8_t use_gyro:1;101uint8_t get_delta_velocity_ret:1;102uint8_t get_delta_angle_ret:1;103uint8_t instance;104uint8_t _end;105};106107// @LoggerMessage: REV2108// @Description: Replay Event (EKF2)109struct log_REV2 {110uint8_t event;111uint8_t _end;112};113114// @LoggerMessage: RSO2115// @Description: Replay Set Origin event (EKF2)116struct log_RSO2 {117int32_t lat;118int32_t lng;119int32_t alt;120uint8_t _end;121};122123// @LoggerMessage: RWA2124// @Description: Replay set-default-airspeed event (EKF2)125struct log_RWA2 {126float airspeed;127float uncertainty;128uint8_t _end;129};130131// same structures for EKF3132// @LoggerMessage: REV3133// @Description: Replay Event (EKF3)134#define log_REV3 log_REV2135// @LoggerMessage: RSO3136// @Description: Replay Set Origin event (EKF3)137#define log_RSO3 log_RSO2138// @LoggerMessage: RWA3139// @Description: Replay set-default-airspeed event (EKF3)140#define log_RWA3 log_RWA2141142// @LoggerMessage: REY3143// @Description: Replay Euler Yaw event144struct log_REY3 {145float yawangle;146float yawangleerr;147uint32_t timestamp_ms;148uint8_t type;149uint8_t _end;150};151152// @LoggerMessage: RBRH153// @Description: Replay Data Barometer Header154struct log_RBRH {155uint8_t primary;156uint8_t num_instances;157uint8_t _end;158};159160// @LoggerMessage: RBRI161// @Description: Replay Data Barometer Instance162struct log_RBRI {163uint32_t last_update_ms;164float altitude; // from get_altitude165bool healthy;166uint8_t instance;167uint8_t _end;168};169170// @LoggerMessage: RRNH171// @Description: Replay Data Rangefinder Header172struct log_RRNH {173// this is rotation-pitch-270!174int16_t ground_clearance_cm;175int16_t max_distance_cm;176uint8_t num_sensors;177uint8_t _end;178};179180// @LoggerMessage: RRNI181// @Description: Replay Data Rangefinder Instance182struct log_RRNI {183Vector3f pos_offset;184uint16_t distance_cm;185uint8_t orientation;186uint8_t status;187uint8_t instance;188uint8_t _end;189};190191// @LoggerMessage: RGPH192// @Description: Replay Data GPS Header193struct log_RGPH {194uint8_t num_sensors;195uint8_t primary_sensor;196uint8_t _end;197};198199// @LoggerMessage: RGPI200// @Description: Replay Data GPS Instance, infrequently changing data201struct log_RGPI {202Vector3f antenna_offset;203float lag_sec;204uint8_t have_vertical_velocity:1;205uint8_t horizontal_accuracy_returncode:1;206uint8_t vertical_accuracy_returncode:1;207uint8_t get_lag_returncode:1;208uint8_t speed_accuracy_returncode:1;209uint8_t gps_yaw_deg_returncode:1;210uint8_t status;211uint8_t num_sats;212uint8_t instance;213uint8_t _end;214};215216// @LoggerMessage: RGPJ217// @Description: Replay Data GPS Instance - rapidly changing data218struct log_RGPJ {219uint32_t last_message_time_ms;220Vector3f velocity;221float sacc;222float yaw_deg;223float yaw_accuracy_deg;224uint32_t yaw_deg_time_ms;225int32_t lat;226int32_t lng;227int32_t alt;228float hacc;229float vacc;230uint16_t hdop;231uint8_t instance;232uint8_t _end;233};234235// @LoggerMessage: RASH236// @Description: Replay Airspeed Sensor Header237struct log_RASH {238uint8_t num_sensors;239uint8_t primary;240uint8_t _end;241};242243// @LoggerMessage: RASI244// @Description: Replay Airspeed Sensor Instance data245struct log_RASI {246float airspeed;247uint32_t last_update_ms;248bool healthy;249bool use;250uint8_t instance;251uint8_t _end;252};253254// @LoggerMessage: RMGH255// @Description: Replay Data Magnetometer Header256struct log_RMGH {257float declination;258bool available;259uint8_t count;260bool auto_declination_enabled;261uint8_t num_enabled;262bool learn_offsets_enabled;263bool consistent;264uint8_t first_usable;265uint8_t _end;266};267268// @LoggerMessage: RMGI269// @Description: Replay Data Magnetometer Instance270struct log_RMGI {271uint32_t last_update_usec;272Vector3f offsets;273Vector3f field;274bool use_for_yaw;275bool healthy;276bool have_scale_factor;277uint8_t instance;278uint8_t _end;279};280281// @LoggerMessage: RBCH282// @Description: Replay Data Beacon Header283struct log_RBCH {284Vector3f vehicle_position_ned;285float accuracy_estimate;286int32_t origin_lat;287int32_t origin_lng;288int32_t origin_alt;289uint8_t get_vehicle_position_ned_returncode:1;290uint8_t get_origin_returncode:1;291uint8_t enabled:1;292uint8_t count;293uint8_t _end;294};295296// @LoggerMessage: RBCI297// @Description: Replay Data Beacon Instance298struct log_RBCI {299uint32_t last_update_ms;300Vector3f position;301float distance;302uint8_t healthy;303uint8_t instance;304uint8_t _end;305};306307// @LoggerMessage: RVOH308// @Description: Replay Data Visual Odometry data309struct log_RVOH {310Vector3f pos_offset;311uint32_t delay_ms;312uint8_t healthy;313bool enabled;314uint8_t _end;315};316317// @LoggerMessage: ROFH318// @Description: Replay optical flow data319struct log_ROFH {320Vector2f rawFlowRates;321Vector2f rawGyroRates;322uint32_t msecFlowMeas;323Vector3f posOffset;324float heightOverride;325uint8_t rawFlowQuality;326uint8_t _end;327};328329// @LoggerMessage: REPH330// @Description: Replay external position data331struct log_REPH {332Vector3f pos;333Quaternion quat;334float posErr;335float angErr;336uint32_t timeStamp_ms;337uint32_t resetTime_ms;338uint16_t delay_ms;339uint8_t _end;340};341342// @LoggerMessage: RSLL343// @Description: Replay Set Lat Lng event344struct log_RSLL {345int32_t lat; // WGS-84 latitude in 1E-7 degrees346int32_t lng; // WGS-84 longitude in 1E7 degrees347float posAccSD; // horizontal position 1 STD uncertainty (m)348uint32_t timestamp_ms;349uint8_t _end;350};351352// @LoggerMessage: REVH353// @Description: Replay external position data354struct log_REVH {355Vector3f vel;356float err;357uint32_t timeStamp_ms;358uint16_t delay_ms;359uint8_t _end;360};361362// @LoggerMessage: RWOH363// @Description: Replay wheel odometry data364struct log_RWOH {365float delAng;366float delTime;367uint32_t timeStamp_ms;368Vector3f posOffset;369float radius;370uint8_t _end;371};372373// @LoggerMessage: RBOH374// @Description: Replay body odometry data375struct log_RBOH {376float quality;377Vector3f delPos;378Vector3f delAng;379float delTime;380uint32_t timeStamp_ms;381Vector3f posOffset;382uint16_t delay_ms;383uint8_t _end;384};385386#define RLOG_SIZE(sname) 3+offsetof(struct log_ ##sname,_end)387388#define LOG_STRUCTURE_FROM_DAL \389{ LOG_RFRH_MSG, RLOG_SIZE(RFRH), \390"RFRH", "QI", "TimeUS,TF", "s-", "F-" }, \391{ LOG_RFRF_MSG, RLOG_SIZE(RFRF), \392"RFRF", "BB", "FTypes,Slow", "--", "--" }, \393{ LOG_RFRN_MSG, RLOG_SIZE(RFRN), \394"RFRN", "IIIfIfffBBB", "HLat,HLon,HAlt,E2T,AM,TX,TY,TZ,VC,EKT,Flags", "DUm????????", "GGB--------" }, \395{ LOG_REV2_MSG, RLOG_SIZE(REV2), \396"REV2", "B", "Event", "-", "-" }, \397{ LOG_RSO2_MSG, RLOG_SIZE(RSO2), \398"RSO2", "III", "Lat,Lon,Alt", "DUm", "GGB" }, \399{ LOG_RWA2_MSG, RLOG_SIZE(RWA2), \400"RWA2", "ff", "Airspeed,uncertainty", "nn", "00" }, \401{ LOG_REV3_MSG, RLOG_SIZE(REV3), \402"REV3", "B", "Event", "-", "-" }, \403{ LOG_RSO3_MSG, RLOG_SIZE(RSO3), \404"RSO3", "III", "Lat,Lon,Alt", "DUm", "GGB" }, \405{ LOG_RWA3_MSG, RLOG_SIZE(RWA3), \406"RWA3", "ff", "Airspeed,Uncertainty", "nn", "00" }, \407{ LOG_REY3_MSG, RLOG_SIZE(REY3), \408"REY3", "ffIB", "yawangle,yawangleerr,timestamp_ms,type", "???-", "???-" }, \409{ LOG_RISH_MSG, RLOG_SIZE(RISH), \410"RISH", "HBBfBB", "LR,PG,PA,LD,AC,GC", "------", "------" }, \411{ LOG_RISI_MSG, RLOG_SIZE(RISI), \412"RISI", "ffffffffBB", "DVX,DVY,DVZ,DAX,DAY,DAZ,DVDT,DADT,Flags,I", "---------#", "----------" }, \413{ LOG_RASH_MSG, RLOG_SIZE(RASH), \414"RASH", "BB", "Primary,NumInst", "--", "--" }, \415{ LOG_RASI_MSG, RLOG_SIZE(RASI), \416"RASI", "fIBBB", "pd,UpdateMS,H,Use,I", "----#", "-----" }, \417{ LOG_RBRH_MSG, RLOG_SIZE(RBRH), \418"RBRH", "BB", "Primary,NumInst", "--", "--" }, \419{ LOG_RBRI_MSG, RLOG_SIZE(RBRI), \420"RBRI", "IfBB", "LastUpdate,Alt,H,I", "---#", "----" }, \421{ LOG_RRNH_MSG, RLOG_SIZE(RRNH), \422"RRNH", "hhB", "GCl,MaxD,NumSensors", "???", "???" }, \423{ LOG_RRNI_MSG, RLOG_SIZE(RRNI), \424"RRNI", "fffHBBB", "PX,PY,PZ,Dist,Orient,Status,I", "------#", "-------" }, \425{ LOG_RGPH_MSG, RLOG_SIZE(RGPH), \426"RGPH", "BB", "NumInst,Primary", "--", "--" }, \427{ LOG_RGPI_MSG, RLOG_SIZE(RGPI), \428"RGPI", "ffffBBBB", "OX,OY,OZ,Lg,Flags,Stat,NSats,I", "-------#", "--------" }, \429{ LOG_RGPJ_MSG, RLOG_SIZE(RGPJ), \430"RGPJ", "IffffffIiiiffHB", "TS,VX,VY,VZ,SA,Y,YA,YT,Lat,Lon,Alt,HA,VA,HD,I", "--------------#", "---------------" }, \431{ LOG_RMGH_MSG, RLOG_SIZE(RMGH), \432"RMGH", "fBBBBBBB", "Dec,Avail,NumInst,AutoDec,NumEna,LOE,C,FUsable", "--------", "--------" }, \433{ LOG_RMGI_MSG, RLOG_SIZE(RMGI), \434"RMGI", "IffffffBBBB", "LU,OX,OY,OZ,FX,FY,FZ,UFY,H,HSF,I", "----------#", "-----------" }, \435{ LOG_RBCH_MSG, RLOG_SIZE(RBCH), \436"RBCH", "ffffiiiBB", "PX,PY,PZ,AE,OLat,OLng,OAlt,Flags,NumInst", "---------", "---------" }, \437{ LOG_RBCI_MSG, RLOG_SIZE(RBCI), \438"RBCI", "IffffBB", "LU,PX,PY,PZ,Dist,H,I", "smmmm-#", "?0000--" }, \439{ LOG_RVOH_MSG, RLOG_SIZE(RVOH), \440"RVOH", "fffIBB", "OX,OY,OZ,Del,H,Ena", "------", "------" }, \441{ LOG_ROFH_MSG, RLOG_SIZE(ROFH), \442"ROFH", "ffffIffffB", "FX,FY,GX,GY,Tms,PX,PY,PZ,HgtOvr,Qual", "----------", "----------" }, \443{ LOG_REPH_MSG, RLOG_SIZE(REPH), \444"REPH", "fffffffffIIH", "PX,PY,PZ,Q1,Q2,Q3,Q4,PEr,AEr,TS,RT,D", "------------", "------------" }, \445{ LOG_RSLL_MSG, RLOG_SIZE(RSLL), \446"RSLL", "IIfI", "Lat,Lng,PosAccSD,TS", "DU--", "GG--" }, \447{ LOG_REVH_MSG, RLOG_SIZE(REVH), \448"REVH", "ffffIH", "VX,VY,VZ,Er,TS,D", "------", "------" }, \449{ LOG_RWOH_MSG, RLOG_SIZE(RWOH), \450"RWOH", "ffIffff", "DA,DT,TS,PX,PY,PZ,R", "-------", "-------" }, \451{ LOG_RBOH_MSG, RLOG_SIZE(RBOH), \452"RBOH", "ffffffffIfffH", "Q,DPX,DPY,DPZ,DAX,DAY,DAZ,DT,TS,OX,OY,OZ,D", "-------------", "-------------" },453454455