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/AC_AttitudeControl/LogStructure.h
Views: 1798
#pragma once12#include <AP_Logger/LogStructure.h>34#define LOG_IDS_FROM_AC_ATTITUDECONTROL \5LOG_PSCN_MSG, \6LOG_PSCE_MSG, \7LOG_PSCD_MSG, \8LOG_PSON_MSG, \9LOG_PSOE_MSG, \10LOG_PSOD_MSG, \11LOG_PSOT_MSG, \12LOG_ANG_MSG1314// @LoggerMessage: PSCN15// @Description: Position Control North16// @Field: TimeUS: Time since system startup17// @Field: DPN: Desired position relative to EKF origin18// @Field: TPN: Target position relative to EKF origin19// @Field: PN: Position relative to EKF origin20// @Field: DVN: Desired velocity North21// @Field: TVN: Target velocity North22// @Field: VN: Velocity North23// @Field: DAN: Desired acceleration North24// @Field: TAN: Target acceleration North25// @Field: AN: Acceleration North2627// @LoggerMessage: PSCE28// @Description: Position Control East29// @Field: TimeUS: Time since system startup30// @Field: DPE: Desired position relative to EKF origin + Offsets31// @Field: TPE: Target position relative to EKF origin32// @Field: PE: Position relative to EKF origin33// @Field: DVE: Desired velocity East34// @Field: TVE: Target velocity East35// @Field: VE: Velocity East36// @Field: DAE: Desired acceleration East37// @Field: TAE: Target acceleration East38// @Field: AE: Acceleration East3940// @LoggerMessage: PSCD41// @Description: Position Control Down42// @Field: TimeUS: Time since system startup43// @Field: DPD: Desired position relative to EKF origin + Offsets44// @Field: TPD: Target position relative to EKF origin45// @Field: PD: Position relative to EKF origin46// @Field: DVD: Desired velocity Down47// @Field: TVD: Target velocity Down48// @Field: VD: Velocity Down49// @Field: DAD: Desired acceleration Down50// @Field: TAD: Target acceleration Down51// @Field: AD: Acceleration Down525354// position controller per-axis logging55struct PACKED log_PSCx {56LOG_PACKET_HEADER;57uint64_t time_us;58float pos_desired;59float pos_target;60float pos;61float vel_desired;62float vel_target;63float vel;64float accel_desired;65float accel_target;66float accel;67};6869// @LoggerMessage: PSON70// @Description: Position Control Offsets North71// @Field: TimeUS: Time since system startup72// @Field: TPON: Target position offset North73// @Field: PON: Position offset North74// @Field: TVON: Target velocity offset North75// @Field: VON: Velocity offset North76// @Field: TAON: Target acceleration offset North77// @Field: AON: Acceleration offset North7879// @LoggerMessage: PSOE80// @Description: Position Control Offsets East81// @Field: TimeUS: Time since system startup82// @Field: TPOE: Target position offset East83// @Field: POE: Position offset East84// @Field: TVOE: Target velocity offset East85// @Field: VOE: Velocity offset East86// @Field: TAOE: Target acceleration offset East87// @Field: AOE: Acceleration offset East8889// @LoggerMessage: PSOD90// @Description: Position Control Offsets Down91// @Field: TimeUS: Time since system startup92// @Field: TPOD: Target position offset Down93// @Field: POD: Position offset Down94// @Field: TVOD: Target velocity offset Down95// @Field: VOD: Velocity offset Down96// @Field: TAOD: Target acceleration offset Down97// @Field: AOD: Acceleration offset Down9899// @LoggerMessage: PSOT100// @Description: Position Control Offsets Terrain (Down)101// @Field: TimeUS: Time since system startup102// @Field: TPOT: Target position offset Terrain103// @Field: POT: Position offset Terrain104// @Field: TVOT: Target velocity offset Terrain105// @Field: VOT: Velocity offset Terrain106// @Field: TAOT: Target acceleration offset Terrain107// @Field: AOT: Acceleration offset Terrain108109// position controller per-axis offset logging110struct PACKED log_PSOx {111LOG_PACKET_HEADER;112uint64_t time_us;113float pos_target_offset;114float pos_offset;115float vel_target_offset;116float vel_offset;117float accel_target_offset;118float accel_offset;119};120121// @LoggerMessage: RATE122// @Description: Desired and achieved vehicle attitude rates. Not logged in Fixed Wing Plane modes.123// @Field: TimeUS: Time since system startup124// @Field: RDes: vehicle desired roll rate125// @Field: R: achieved vehicle roll rate126// @Field: ROut: normalized output for Roll127// @Field: PDes: vehicle desired pitch rate128// @Field: P: vehicle pitch rate129// @Field: POut: normalized output for Pitch130// @Field: Y: achieved vehicle yaw rate131// @Field: YOut: normalized output for Yaw132// @Field: YDes: vehicle desired yaw rate133// @Field: ADes: desired vehicle vertical acceleration134// @Field: A: achieved vehicle vertical acceleration135// @Field: AOut: percentage of vertical thrust output current being used136// @Field: AOutSlew: vertical thrust output slew rate137struct PACKED log_Rate {138LOG_PACKET_HEADER;139uint64_t time_us;140float control_roll;141float roll;142float roll_out;143float control_pitch;144float pitch;145float pitch_out;146float control_yaw;147float yaw;148float yaw_out;149float control_accel;150float accel;151float accel_out;152float throttle_slew;153};154155// @LoggerMessage: ANG156// @Description: Attitude control attitude157// @Field: TimeUS: Timestamp of the current Attitude loop158// @Field: DesRoll: vehicle desired roll159// @Field: Roll: achieved vehicle roll160// @Field: DesPitch: vehicle desired pitch161// @Field: Pitch: achieved vehicle pitch162// @Field: DesYaw: vehicle desired yaw163// @Field: Yaw: achieved vehicle yaw164// @Field: Dt: attitude delta time165struct PACKED log_ANG {166LOG_PACKET_HEADER;167uint64_t time_us;168float control_roll;169float roll;170float control_pitch;171float pitch;172float control_yaw;173float yaw;174float sensor_dt;175};176177#define PSCx_FMT "Qfffffffff"178#define PSCx_UNITS "smmmnnnooo"179#define PSCx_MULTS "F000000000"180181#define PSOx_FMT "Qffffff"182#define PSOx_UNITS "smmnnoo"183#define PSOx_MULTS "F000000"184185#define LOG_STRUCTURE_FROM_AC_ATTITUDECONTROL \186{ LOG_PSCN_MSG, sizeof(log_PSCx), \187"PSCN", PSCx_FMT, "TimeUS,DPN,TPN,PN,DVN,TVN,VN,DAN,TAN,AN", PSCx_UNITS, PSCx_MULTS }, \188{ LOG_PSCE_MSG, sizeof(log_PSCx), \189"PSCE", PSCx_FMT, "TimeUS,DPE,TPE,PE,DVE,TVE,VE,DAE,TAE,AE", PSCx_UNITS, PSCx_MULTS }, \190{ LOG_PSCD_MSG, sizeof(log_PSCx), \191"PSCD", PSCx_FMT, "TimeUS,DPD,TPD,PD,DVD,TVD,VD,DAD,TAD,AD", PSCx_UNITS, PSCx_MULTS }, \192{ LOG_PSON_MSG, sizeof(log_PSOx), \193"PSON", PSOx_FMT, "TimeUS,TPON,PON,TVON,VON,TAON,AON", PSOx_UNITS, PSOx_MULTS }, \194{ LOG_PSOE_MSG, sizeof(log_PSOx), \195"PSOE", PSOx_FMT, "TimeUS,TPOE,POE,TVOE,VOE,TAOE,AOE", PSOx_UNITS, PSOx_MULTS }, \196{ LOG_PSOD_MSG, sizeof(log_PSOx), \197"PSOD", PSOx_FMT, "TimeUS,TPOD,POD,TVOD,VOD,TAOD,AOD", PSOx_UNITS, PSOx_MULTS }, \198{ LOG_PSOT_MSG, sizeof(log_PSOx), \199"PSOT", PSOx_FMT, "TimeUS,TPOT,POT,TVOT,VOT,TAOT,AOT", PSOx_UNITS, PSOx_MULTS }, \200{ LOG_RATE_MSG, sizeof(log_Rate), \201"RATE", "Qfffffffffffff", "TimeUS,RDes,R,ROut,PDes,P,POut,YDes,Y,YOut,ADes,A,AOut,AOutSlew", "skk-kk-kk-oo--", "F?????????BB--" , true }, \202{ LOG_ANG_MSG, sizeof(log_ANG),\203"ANG", "Qfffffff", "TimeUS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,Dt", "sddddhhs", "F0000000" , true }204205206