mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AP_Logger: trim LogStructure base off included code
This commit is contained in:
parent
a3aaaf3691
commit
10ef10da45
@ -142,6 +142,7 @@ const struct MultiplierStructure log_Multipliers[] = {
|
||||
#include <AP_HAL_ChibiOS/LogStructure.h>
|
||||
#include <AP_RPM/LogStructure.h>
|
||||
#include <AC_Fence/LogStructure.h>
|
||||
#include <AP_Landing/LogStructure.h>
|
||||
|
||||
// structure used to define logging format
|
||||
// It is packed on ChibiOS to save flash space; however, this causes problems
|
||||
@ -577,24 +578,6 @@ struct PACKED log_SRTL {
|
||||
float D;
|
||||
};
|
||||
|
||||
struct PACKED log_DSTL {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
uint8_t stage;
|
||||
float target_heading;
|
||||
int32_t target_lat;
|
||||
int32_t target_lng;
|
||||
int32_t target_alt;
|
||||
int16_t crosstrack_error;
|
||||
int16_t travel_distance;
|
||||
float l1_i;
|
||||
int32_t loiter_sum_cd;
|
||||
float desired;
|
||||
float P;
|
||||
float I;
|
||||
float D;
|
||||
};
|
||||
|
||||
struct PACKED log_Arm_Disarm {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
@ -795,23 +778,6 @@ struct PACKED log_VER {
|
||||
// @Field: FMx: Maximum free space in write buffer in last time period
|
||||
// @Field: FAv: Average free space in write buffer in last time period
|
||||
|
||||
// @LoggerMessage: DSTL
|
||||
// @Description: Deepstall Landing data
|
||||
// @Field: TimeUS: Time since system startup
|
||||
// @Field: Stg: Deepstall landing stage
|
||||
// @Field: THdg: Target heading
|
||||
// @Field: Lat: Landing point latitude
|
||||
// @Field: Lng: Landing point longitude
|
||||
// @Field: Alt: Landing point altitude
|
||||
// @Field: XT: Crosstrack error
|
||||
// @Field: Travel: Expected travel distance vehicle will travel from this point
|
||||
// @Field: L1I: L1 controller crosstrack integrator value
|
||||
// @Field: Loiter: wind estimate loiter angle flown
|
||||
// @Field: Des: Deepstall steering PID desired value
|
||||
// @Field: P: Deepstall steering PID Proportional response component
|
||||
// @Field: I: Deepstall steering PID Integral response component
|
||||
// @Field: D: Deepstall steering PID Derivative response component
|
||||
|
||||
// @LoggerMessage: ERR
|
||||
// @Description: Specifically coded error messages
|
||||
// @Field: TimeUS: Time since system startup
|
||||
@ -1300,8 +1266,7 @@ LOG_STRUCTURE_FROM_ESC_TELEM \
|
||||
"PIDN", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true }, \
|
||||
{ LOG_PIDE_MSG, sizeof(log_PID), \
|
||||
"PIDE", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true }, \
|
||||
{ LOG_DSTL_MSG, sizeof(log_DSTL), \
|
||||
"DSTL", "QBfLLeccfeffff", "TimeUS,Stg,THdg,Lat,Lng,Alt,XT,Travel,L1I,Loiter,Des,P,I,D", "s??DUm--------", "F??000--------" , true }, \
|
||||
LOG_STRUCTURE_FROM_LANDING \
|
||||
LOG_STRUCTURE_FROM_INERTIALSENSOR \
|
||||
LOG_STRUCTURE_FROM_DAL \
|
||||
LOG_STRUCTURE_FROM_NAVEKF2 \
|
||||
@ -1388,7 +1353,7 @@ enum LogMessages : uint8_t {
|
||||
LOG_PIDS_MSG,
|
||||
LOG_PIDN_MSG,
|
||||
LOG_PIDE_MSG,
|
||||
LOG_DSTL_MSG,
|
||||
LOG_IDS_FROM_LANDING,
|
||||
LOG_MAG_MSG,
|
||||
LOG_ARSP_MSG,
|
||||
LOG_IDS_FROM_RPM,
|
||||
|
Loading…
Reference in New Issue
Block a user