APM:Copter
Log.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 #if LOGGING_ENABLED == ENABLED
4 
5 // Code to Write and Read packets from DataFlash log memory
6 // Code to interact with the user to dump or erase logs
7 
8 #if AUTOTUNE_ENABLED == ENABLED
11  uint64_t time_us;
12  uint8_t axis; // roll or pitch
13  uint8_t tune_step; // tuning PI or D up or down
14  float meas_target; // target achieved rotation rate
15  float meas_min; // maximum achieved rotation rate
16  float meas_max; // maximum achieved rotation rate
17  float new_gain_rp; // newly calculated gain
18  float new_gain_rd; // newly calculated gain
19  float new_gain_sp; // newly calculated gain
20  float new_ddt; // newly calculated gain
21 };
22 
23 // Write an Autotune data packet
24 void Copter::ModeAutoTune::Log_Write_AutoTune(uint8_t _axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt)
25 {
26  struct log_AutoTune pkt = {
29  axis : _axis,
37  new_ddt : new_ddt
38  };
39  copter.DataFlash.WriteBlock(&pkt, sizeof(pkt));
40 }
41 
44  uint64_t time_us;
45  float angle_cd; // lean angle in centi-degrees
46  float rate_cds; // current rotation rate in centi-degrees / second
47 };
48 
49 // Write an Autotune data packet
50 void Copter::ModeAutoTune::Log_Write_AutoTuneDetails(float angle_cd, float rate_cds)
51 {
52  struct log_AutoTuneDetails pkt = {
56  rate_cds : rate_cds
57  };
58  copter.DataFlash.WriteBlock(&pkt, sizeof(pkt));
59 }
60 #endif
61 
64  uint64_t time_us;
65  uint8_t surface_quality;
66  float flow_x;
67  float flow_y;
68  float body_x;
69  float body_y;
70 };
71 
72 // Write an optical flow packet
74 {
75  #if OPTFLOW == ENABLED
76  // exit immediately if not enabled
77  if (!optflow.enabled()) {
78  return;
79  }
80  const Vector2f &flowRate = optflow.flowRate();
81  const Vector2f &bodyRate = optflow.bodyRate();
82  struct log_Optflow pkt = {
85  surface_quality : optflow.quality(),
86  flow_x : flowRate.x,
87  flow_y : flowRate.y,
88  body_x : bodyRate.x,
89  body_y : bodyRate.y
90  };
91  DataFlash.WriteBlock(&pkt, sizeof(pkt));
92  #endif // OPTFLOW == ENABLED
93 }
94 
97  uint64_t time_us;
98  float throttle_in;
99  float angle_boost;
102  float desired_alt;
103  float inav_alt;
104  int32_t baro_alt;
107  float terr_alt;
109  int16_t climb_rate;
110 };
111 
112 // Write a control tuning packet
114 {
115  // get terrain altitude
116  float terr_alt = 0.0f;
117 #if AP_TERRAIN_AVAILABLE && AC_TERRAIN
118  if (!terrain.height_above_terrain(terr_alt, true)) {
119  terr_alt = DataFlash.quiet_nan();
120  }
121 #endif
122 
123  struct log_Control_Tuning pkt = {
126  throttle_in : attitude_control->get_throttle_in(),
127  angle_boost : attitude_control->angle_boost(),
130  desired_alt : pos_control->get_alt_target() / 100.0f,
131  inav_alt : inertial_nav.get_altitude() / 100.0f,
132  baro_alt : baro_alt,
133  desired_rangefinder_alt : (int16_t)target_rangefinder_alt,
134  rangefinder_alt : rangefinder_state.alt_cm,
135  terr_alt : terr_alt,
136  target_climb_rate : (int16_t)pos_control->get_vel_target_z(),
138  };
139  DataFlash.WriteBlock(&pkt, sizeof(pkt));
140 }
141 
142 // Write an attitude packet
144 {
145  Vector3f targets = attitude_control->get_att_target_euler_cd();
146  targets.z = wrap_360_cd(targets.z);
148  DataFlash.Log_Write_Rate(ahrs, *motors, *attitude_control, *pos_control);
149  if (should_log(MASK_LOG_PID)) {
150  DataFlash.Log_Write_PID(LOG_PIDR_MSG, attitude_control->get_rate_roll_pid().get_pid_info());
151  DataFlash.Log_Write_PID(LOG_PIDP_MSG, attitude_control->get_rate_pitch_pid().get_pid_info());
152  DataFlash.Log_Write_PID(LOG_PIDY_MSG, attitude_control->get_rate_yaw_pid().get_pid_info());
153  DataFlash.Log_Write_PID(LOG_PIDA_MSG, pos_control->get_accel_z_pid().get_pid_info() );
154  }
155 }
156 
157 // Write an EKF and POS packet
159 {
160  DataFlash.Log_Write_EKF(ahrs);
162 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
164 #endif
166 }
167 
170  uint64_t time_us;
171  float lift_max;
172  float bat_volt;
173  float bat_res;
174  float th_limit;
175 };
176 
177 // Write an rate packet
179 {
180 #if FRAME_CONFIG != HELI_FRAME
181  struct log_MotBatt pkt_mot = {
184  lift_max : (float)(motors->get_lift_max()),
185  bat_volt : (float)(motors->get_batt_voltage_filt()),
186  bat_res : (float)(battery.get_resistance()),
187  th_limit : (float)(motors->get_throttle_limit())
188  };
189  DataFlash.WriteBlock(&pkt_mot, sizeof(pkt_mot));
190 #endif
191 }
192 
195  uint64_t time_us;
196  uint8_t id;
197 };
198 
199 // Wrote an event packet
200 void Copter::Log_Write_Event(uint8_t id)
201 {
202  if (should_log(MASK_LOG_ANY)) {
203  struct log_Event pkt = {
206  id : id
207  };
208  DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
209  }
210 }
211 
214  uint64_t time_us;
215  uint8_t id;
216  int16_t data_value;
217 };
218 
219 // Write an int16_t data packet
221 void Copter::Log_Write_Data(uint8_t id, int16_t value)
222 {
223  if (should_log(MASK_LOG_ANY)) {
224  struct log_Data_Int16t pkt = {
227  id : id,
228  data_value : value
229  };
230  DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
231  }
232 }
233 
236  uint64_t time_us;
237  uint8_t id;
238  uint16_t data_value;
239 };
240 
241 // Write an uint16_t data packet
243 void Copter::Log_Write_Data(uint8_t id, uint16_t value)
244 {
245  if (should_log(MASK_LOG_ANY)) {
246  struct log_Data_UInt16t pkt = {
249  id : id,
250  data_value : value
251  };
252  DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
253  }
254 }
255 
258  uint64_t time_us;
259  uint8_t id;
260  int32_t data_value;
261 };
262 
263 // Write an int32_t data packet
264 void Copter::Log_Write_Data(uint8_t id, int32_t value)
265 {
266  if (should_log(MASK_LOG_ANY)) {
267  struct log_Data_Int32t pkt = {
270  id : id,
271  data_value : value
272  };
273  DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
274  }
275 }
276 
279  uint64_t time_us;
280  uint8_t id;
281  uint32_t data_value;
282 };
283 
284 // Write a uint32_t data packet
285 void Copter::Log_Write_Data(uint8_t id, uint32_t value)
286 {
287  if (should_log(MASK_LOG_ANY)) {
288  struct log_Data_UInt32t pkt = {
291  id : id,
292  data_value : value
293  };
294  DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
295  }
296 }
297 
300  uint64_t time_us;
301  uint8_t id;
302  float data_value;
303 };
304 
305 // Write a float data packet
307 void Copter::Log_Write_Data(uint8_t id, float value)
308 {
309  if (should_log(MASK_LOG_ANY)) {
310  struct log_Data_Float pkt = {
313  id : id,
314  data_value : value
315  };
316  DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
317  }
318 }
319 
322  uint64_t time_us;
323  uint8_t sub_system;
324  uint8_t error_code;
325 };
326 
327 // Write an error packet
328 void Copter::Log_Write_Error(uint8_t sub_system, uint8_t error_code)
329 {
330  struct log_Error pkt = {
335  };
336  DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
337 }
338 
341  uint64_t time_us;
342  uint8_t parameter; // parameter we are tuning, e.g. 39 is CH6_CIRCLE_RATE
343  float tuning_value; // normalized value used inside tuning() function
344  int16_t control_in; // raw tune input value
345  int16_t tuning_low; // tuning low end value
346  int16_t tuning_high; // tuning high end value
347 };
348 
349 void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high)
350 {
351  struct log_ParameterTuning pkt_tune = {
354  parameter : param,
355  tuning_value : tuning_val,
357  tuning_low : tune_low,
358  tuning_high : tune_high
359  };
360 
361  DataFlash.WriteBlock(&pkt_tune, sizeof(pkt_tune));
362 }
363 
364 // logs when baro or compass becomes unhealthy
366 {
367  // check baro
368  if (sensor_health.baro != barometer.healthy()) {
369  sensor_health.baro = barometer.healthy();
370  Log_Write_Error(ERROR_SUBSYSTEM_BARO, (sensor_health.baro ? ERROR_CODE_ERROR_RESOLVED : ERROR_CODE_UNHEALTHY));
371  }
372 
373  // check compass
374  if (sensor_health.compass != compass.healthy()) {
375  sensor_health.compass = compass.healthy();
376  Log_Write_Error(ERROR_SUBSYSTEM_COMPASS, (sensor_health.compass ? ERROR_CODE_ERROR_RESOLVED : ERROR_CODE_UNHEALTHY));
377  }
378 
379  // check primary GPS
380  if (sensor_health.primary_gps != gps.primary_sensor()) {
381  sensor_health.primary_gps = gps.primary_sensor();
382  Log_Write_Event(DATA_GPS_PRIMARY_CHANGED);
383  }
384 }
385 
386 struct PACKED log_Heli {
388  uint64_t time_us;
391 };
392 
393 #if FRAME_CONFIG == HELI_FRAME
394 // Write an helicopter packet
395 void Copter::Log_Write_Heli()
396 {
397  struct log_Heli pkt_heli = {
400  desired_rotor_speed : motors->get_desired_rotor_speed(),
401  main_rotor_speed : motors->get_main_rotor_speed(),
402  };
403  DataFlash.WriteBlock(&pkt_heli, sizeof(pkt_heli));
404 }
405 #endif
406 
407 // precision landing logging
410  uint64_t time_us;
411  uint8_t healthy;
413  float pos_x;
414  float pos_y;
415  float vel_x;
416  float vel_y;
417 };
418 
419 // Write an optical flow packet
421 {
422  #if PRECISION_LANDING == ENABLED
423  // exit immediately if not enabled
424  if (!precland.enabled()) {
425  return;
426  }
427 
428  Vector2f target_pos_rel = Vector2f(0.0f,0.0f);
429  Vector2f target_vel_rel = Vector2f(0.0f,0.0f);
430  precland.get_target_position_relative_cm(target_pos_rel);
431  precland.get_target_velocity_relative_cms(target_vel_rel);
432 
433  struct log_Precland pkt = {
436  healthy : precland.healthy(),
437  target_acquired : precland.target_acquired(),
438  pos_x : target_pos_rel.x,
439  pos_y : target_pos_rel.y,
440  vel_x : target_vel_rel.x,
441  vel_y : target_vel_rel.y
442  };
443  DataFlash.WriteBlock(&pkt, sizeof(pkt));
444  #endif // PRECISION_LANDING == ENABLED
445 }
446 
447 // precision landing logging
450  uint64_t time_us;
451  uint8_t type;
458 };
459 
460 // Write a Guided mode target
461 void Copter::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target)
462 {
463  struct log_GuidedTarget pkt = {
466  type : target_type,
467  pos_target_x : pos_target.x,
468  pos_target_y : pos_target.y,
469  pos_target_z : pos_target.z,
470  vel_target_x : vel_target.x,
471  vel_target_y : vel_target.y,
472  vel_target_z : vel_target.z
473  };
474  DataFlash.WriteBlock(&pkt, sizeof(pkt));
475 }
476 
477 // type and unit information can be found in
478 // libraries/DataFlash/Logstructure.h; search for "log_Units" for
479 // units and "Format characters" for field type information
480 const struct LogStructure Copter::log_structure[] = {
482 #if AUTOTUNE_ENABLED == ENABLED
483  { LOG_AUTOTUNE_MSG, sizeof(log_AutoTune),
484  "ATUN", "QBBfffffff", "TimeUS,Axis,TuneStep,Targ,Min,Max,RP,RD,SP,ddt", "s--ddd---o", "F--BBB---0" },
486  "ATDE", "Qff", "TimeUS,Angle,Rate", "sdk", "FBB" },
487 #endif
489  "PTUN", "QBfHHH", "TimeUS,Param,TunVal,CtrlIn,TunLo,TunHi", "s-----", "F-----" },
490 #if OPTFLOW == ENABLED
491  { LOG_OPTFLOW_MSG, sizeof(log_Optflow),
492  "OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY", "s-EEEE", "F-0000" },
493 #endif
495  "CTUN", "Qffffffeccfhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00BBBBBB" },
496  { LOG_MOTBATT_MSG, sizeof(log_MotBatt),
497  "MOTB", "Qffff", "TimeUS,LiftMax,BatVolt,BatRes,ThLimit", "s-vw-", "F-00-" },
498  { LOG_EVENT_MSG, sizeof(log_Event),
499  "EV", "QB", "TimeUS,Id", "s-", "F-" },
501  "D16", "QBh", "TimeUS,Id,Value", "s--", "F--" },
503  "DU16", "QBH", "TimeUS,Id,Value", "s--", "F--" },
505  "D32", "QBi", "TimeUS,Id,Value", "s--", "F--" },
507  "DU32", "QBI", "TimeUS,Id,Value", "s--", "F--" },
509  "DFLT", "QBf", "TimeUS,Id,Value", "s--", "F--" },
510  { LOG_ERROR_MSG, sizeof(log_Error),
511  "ERR", "QBB", "TimeUS,Subsys,ECode", "s--", "F--" },
513  { LOG_HELI_MSG, sizeof(log_Heli),
514  "HELI", "Qff", "TimeUS,DRRPM,ERRPM", "s--", "F--" },
515 #endif
517  { LOG_PRECLAND_MSG, sizeof(log_Precland),
518  "PL", "QBBffff", "TimeUS,Heal,TAcq,pX,pY,vX,vY", "s--ddmm","F--00BB" },
519 #endif
521  "GUID", "QBffffff", "TimeUS,Type,pX,pY,pZ,vX,vY,vZ", "s-mmmnnn", "F-000000" },
522 };
523 
525 {
526  // only 200(?) bytes are guaranteed by DataFlash
527  DataFlash.Log_Write_MessageF("Frame: %s", get_frame_string());
528  DataFlash.Log_Write_Mode(control_mode, control_mode_reason);
529 #if AC_RALLY
530  DataFlash.Log_Write_Rally(rally);
531 #endif
534 }
535 
536 
538 {
539  DataFlash.Init(log_structure, ARRAY_SIZE(log_structure));
540 }
541 
542 #else // LOGGING_ENABLED
543 
546 void Copter::Log_Write_Attitude(void) {}
549 void Copter::Log_Write_Event(uint8_t id) {}
550 void Copter::Log_Write_Data(uint8_t id, int32_t value) {}
551 void Copter::Log_Write_Data(uint8_t id, uint32_t value) {}
552 void Copter::Log_Write_Data(uint8_t id, int16_t value) {}
553 void Copter::Log_Write_Data(uint8_t id, uint16_t value) {}
554 void Copter::Log_Write_Data(uint8_t id, float value) {}
555 void Copter::Log_Write_Error(uint8_t sub_system, uint8_t error_code) {}
556 void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high) {}
559 void Copter::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target) {}
561 
562 #if FRAME_CONFIG == HELI_FRAME
563 void Copter::Log_Write_Heli() {}
564 #endif
565 
566 #if OPTFLOW == ENABLED
568 #endif
569 
570 void Copter::log_init(void) {}
571 
572 #endif // LOGGING_ENABLED
#define ERROR_CODE_UNHEALTHY
Definition: defines.h:420
#define HELI_FRAME
Definition: defines.h:84
Compass & compass()
float meas_target
Definition: Log.cpp:14
uint64_t time_us
Definition: Log.cpp:322
void Log_Write_MessageF(const char *fmt,...)
LOG_PIDR_MSG
uint8_t id
Definition: Log.cpp:259
uint64_t time_us
Definition: Log.cpp:236
uint8_t target_acquired
Definition: Log.cpp:412
int16_t climb_rate
Definition: Log.cpp:109
#define MASK_LOG_PID
Definition: defines.h:326
LOG_PACKET_HEADER
Definition: Log.cpp:169
float new_gain_rp
Definition: Log.cpp:17
float pos_x
Definition: Log.cpp:413
void Log_Write_Control_Tuning()
Definition: Log.cpp:113
float angle_cd
Definition: Log.cpp:45
uint64_t time_us
Definition: Log.cpp:300
float flow_y
Definition: Log.cpp:67
uint64_t time_us
Definition: Log.cpp:450
LOG_PIDY_MSG
float desired_rotor_speed
Definition: Log.cpp:389
float pos_y
Definition: Log.cpp:414
uint64_t time_us
Definition: Log.cpp:214
AP_AHRS_NavEKF & ahrs
#define FRAME_CONFIG
Definition: config.h:59
void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt)
Definition: Log.cpp:24
float data_value
Definition: Log.cpp:302
float meas_min
Definition: Log.cpp:15
float body_x
Definition: Log.cpp:68
auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f))
uint8_t id
Definition: Log.cpp:280
int16_t data_value
Definition: Log.cpp:216
float bat_volt
Definition: Log.cpp:172
void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds)
Definition: Log.cpp:50
float terr_alt
Definition: Log.cpp:107
void Log_Write_Mode(uint8_t mode, uint8_t reason)
int16_t control_in
Definition: Log.cpp:344
void Log_Write_SIMSTATE(DataFlash_Class *dataflash)
void Log_Write_Rate(const AP_AHRS &ahrs, const AP_Motors &motors, const AC_AttitudeControl &attitude_control, const AC_PosControl &pos_control)
void Log_Write_Optflow()
Definition: Log.cpp:73
void WriteBlock(const void *pBuffer, uint16_t size)
float bat_res
Definition: Log.cpp:173
#define ERROR_SUBSYSTEM_COMPASS
Definition: defines.h:395
float desired_alt
Definition: Log.cpp:102
float th_limit
Definition: Log.cpp:174
void Log_Write_EKF_POS()
Definition: Log.cpp:158
float vel_target_y
Definition: Log.cpp:456
int32_t baro_alt
Definition: Log.cpp:104
uint16_t data_value
Definition: Log.cpp:238
void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f &pos_target, const Vector3f &vel_target)
Definition: Log.cpp:461
void Log_Write_Home_And_Origin()
uint64_t time_us
Definition: Log.cpp:341
uint64_t time_us
Definition: Log.cpp:258
void Log_Write_Vehicle_Startup_Messages()
Definition: Log.cpp:524
void Log_Write_Precland()
Definition: Log.cpp:420
void Log_Write_PID(uint8_t msg_type, const PID_Info &info)
uint64_t time_us
Definition: Log.cpp:279
uint64_t time_us
Definition: Log.cpp:11
#define UNUSED_FUNCTION
AP_MotorsMatrix motors(400)
SITL::SITL * sitl()
int32_t data_value
Definition: Log.cpp:260
float vel_y
Definition: Log.cpp:416
uint64_t time_us
Definition: Log.cpp:195
void Log_Write_Performance()
void log_init(void)
Definition: Log.cpp:537
void Log_Write_Error(uint8_t sub_system, uint8_t error_code)
Definition: Log.cpp:328
LOG_PACKET_HEADER
Definition: Log.cpp:194
LOG_COMMON_STRUCTURES
Definition: Log.cpp:481
uint8_t id
Definition: Log.cpp:301
float main_rotor_speed
Definition: Log.cpp:390
void Init(const struct LogStructure *structure, uint8_t num_types)
float rate_cds
Definition: Log.cpp:46
void Log_Write_MotBatt()
Definition: Log.cpp:178
float throttle_hover
Definition: Log.cpp:101
float angle_boost
Definition: Log.cpp:99
uint64_t time_us
Definition: Log.cpp:410
float vel_x
Definition: Log.cpp:415
void Log_Write_Rally(const AP_Rally &rally)
virtual float get_throttle_hover() const
int16_t desired_rangefinder_alt
Definition: Log.cpp:105
float vel_target_z
Definition: Log.cpp:457
int16_t rangefinder_alt
Definition: Log.cpp:106
#define f(i)
void Log_Write_POS(AP_AHRS &ahrs)
LOG_PACKET_HEADER
Definition: Log.cpp:321
#define ERROR_SUBSYSTEM_BARO
Definition: defines.h:410
void Log_Write_Attitude()
Definition: Log.cpp:143
void Log_Write_Event(uint8_t id)
Definition: Log.cpp:200
uint8_t axis
Definition: Log.cpp:12
float pos_target_z
Definition: Log.cpp:454
uint64_t time_us
Definition: Log.cpp:97
uint8_t id
Definition: Log.cpp:196
void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets)
float flow_x
Definition: Log.cpp:66
uint64_t micros64()
LOG_PIDP_MSG
bool healthy[COMPASS_MAX_INSTANCES]
LOG_PIDA_MSG
void Log_Write_AHRS2(AP_AHRS &ahrs)
#define ARRAY_SIZE(_arr)
uint8_t surface_quality
Definition: Log.cpp:65
uint8_t error_code
Definition: Log.cpp:324
int16_t target_climb_rate
Definition: Log.cpp:108
void WriteCriticalBlock(const void *pBuffer, uint16_t size)
float get_batt_voltage_filt() const
float new_gain_sp
Definition: Log.cpp:19
AP_BattMonitor & battery()
float tuning_value
Definition: Log.cpp:343
uint32_t data_value
Definition: Log.cpp:281
uint8_t type
Definition: Log.cpp:451
uint8_t healthy
Definition: Log.cpp:411
float body_y
Definition: Log.cpp:69
LOG_PACKET_HEADER
Definition: Log.cpp:409
float pos_target_x
Definition: Log.cpp:452
DataFlash_Class DataFlash
LOG_PACKET_HEADER
Definition: Log.cpp:63
uint64_t time_us
Definition: Log.cpp:388
uint8_t parameter
Definition: Log.cpp:342
void Log_Sensor_Health()
Definition: Log.cpp:365
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
float throttle_in
Definition: Log.cpp:98
float vel_target_x
Definition: Log.cpp:455
float throttle_out
Definition: Log.cpp:100
float inav_alt
Definition: Log.cpp:103
uint8_t primary_sensor(void) const
float lift_max
Definition: Log.cpp:171
#define PRECISION_LANDING
Definition: config.h:229
#define PACKED
float new_ddt
Definition: Log.cpp:20
uint64_t time_us
Definition: Log.cpp:44
float meas_max
Definition: Log.cpp:16
int16_t tuning_high
Definition: Log.cpp:346
float value
LOG_PACKET_HEADER
Definition: Log.cpp:10
LOG_PACKET_HEADER
Definition: Log.cpp:387
#define ERROR_CODE_ERROR_RESOLVED
Definition: defines.h:418
AP_GPS & gps()
uint8_t id
Definition: Log.cpp:215
float get_throttle() const
#define ENABLED
Definition: defines.h:6
uint8_t tune_step
Definition: Log.cpp:13
#define OPTFLOW
Definition: config.h:208
float get_resistance() const
uint64_t time_us
Definition: Log.cpp:64
#define LOG_PACKET_HEADER_INIT(id)
int16_t tuning_low
Definition: Log.cpp:345
#define DATA_GPS_PRIMARY_CHANGED
Definition: defines.h:387
float get_throttle_limit() const
float pos_target_y
Definition: Log.cpp:453
uint8_t sub_system
Definition: Log.cpp:323
double quiet_nan() const
uint64_t time_us
Definition: Log.cpp:170
void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high)
Definition: Log.cpp:349
void Log_Write_Data(uint8_t id, int32_t value)
Definition: Log.cpp:264
float new_gain_rd
Definition: Log.cpp:18
#define MASK_LOG_ANY
Definition: defines.h:333
void Write_DataFlash_Log_Startup_messages()
uint8_t id
Definition: Log.cpp:237