APM:Libraries
DataFlash.h
Go to the documentation of this file.
1 /* ************************************************************ */
2 /* Test for DataFlash Log library */
3 /* ************************************************************ */
4 #pragma once
5 
6 #include <AP_HAL/AP_HAL.h>
7 #include <AP_Common/AP_Common.h>
8 #include <AP_Param/AP_Param.h>
9 #include <AP_GPS/AP_GPS.h>
11 #include <AP_RSSI/AP_RSSI.h>
12 #include <AP_Baro/AP_Baro.h>
13 #include <AP_AHRS/AP_AHRS.h>
14 #include <AP_Vehicle/AP_Vehicle.h>
15 #include <AP_Mission/AP_Mission.h>
18 #include <AP_RPM/AP_RPM.h>
20 #include <DataFlash/LogStructure.h>
21 #include <AP_Motors/AP_Motors.h>
22 #include <AP_Rally/AP_Rally.h>
23 #include <AP_Beacon/AP_Beacon.h>
26 
27 #include <stdint.h>
28 
29 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
30 #include <uORB/topics/esc_status.h>
31 #endif
32 
33 #include "DFMessageWriter.h"
34 
35 class DataFlash_Backend;
36 
42 };
43 
44 // fwd declarations to avoid include errors
45 class AC_AttitudeControl;
46 class AC_PosControl;
47 
49 {
50  friend class DataFlash_Backend; // for _num_types
51 
52 public:
53  FUNCTOR_TYPEDEF(vehicle_startup_message_Log_Writer, void);
54 
55  DataFlash_Class(const char *firmware_string, const AP_Int32 &log_bitmask);
56 
57  /* Do not allow copies */
58  DataFlash_Class(const DataFlash_Class &other) = delete;
59  DataFlash_Class &operator=(const DataFlash_Class&) = delete;
60 
61  // get singleton instance
62  static DataFlash_Class *instance(void) {
63  return _instance;
64  }
65 
66  void set_mission(const AP_Mission *mission);
67 
68  // initialisation
69  void Init(const struct LogStructure *structure, uint8_t num_types);
70 
71  bool CardInserted(void);
72 
73  // erase handling
74  void EraseAll();
75 
76  /* Write a block of data at current offset */
77  void WriteBlock(const void *pBuffer, uint16_t size);
78  /* Write an *important* block of data at current offset */
79  void WriteCriticalBlock(const void *pBuffer, uint16_t size);
80 
81  // high level interface
82  uint16_t find_last_log() const;
83  void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
84  uint16_t get_num_logs(void);
85 
86  void setVehicle_Startup_Log_Writer(vehicle_startup_message_Log_Writer writer);
87 
88  void PrepForArming();
89 
90  void EnableWrites(bool enable) { _writes_enabled = enable; }
91  bool WritesEnabled() const { return _writes_enabled; }
92 
93  void StopLogging();
94 
95  void Log_Write_Parameter(const char *name, float value);
96  void Log_Write_GPS(uint8_t instance, uint64_t time_us=0);
97  void Log_Write_RFND(const RangeFinder &rangefinder);
98  void Log_Write_IMU();
99  void Log_Write_IMUDT(uint64_t time_us, uint8_t imu_mask);
100  bool Log_Write_ISBH(uint16_t seqno,
102  uint8_t instance,
103  uint16_t multiplier,
104  uint16_t sample_count,
105  uint64_t sample_us,
106  float sample_rate_hz);
107  bool Log_Write_ISBD(uint16_t isb_seqno,
108  uint16_t seqno,
109  const int16_t x[32],
110  const int16_t y[32],
111  const int16_t z[32]);
112  void Log_Write_Vibration();
113  void Log_Write_RCIN(void);
114  void Log_Write_RCOUT(void);
115  void Log_Write_RSSI(AP_RSSI &rssi);
116  void Log_Write_Baro(uint64_t time_us=0);
117  void Log_Write_Power(void);
119  void Log_Write_POS(AP_AHRS &ahrs);
120 #if AP_AHRS_NAVEKF_AVAILABLE
121  void Log_Write_EKF(AP_AHRS_NavEKF &ahrs);
122 #endif
123  bool Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t& mav_cmd);
124  void Log_Write_Radio(const mavlink_radio_t &packet);
125  void Log_Write_Message(const char *message);
126  void Log_Write_MessageF(const char *fmt, ...);
127  void Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const Location &current_loc);
128  void Log_Write_Camera(const AP_AHRS &ahrs, const Location &current_loc);
129  void Log_Write_Trigger(const AP_AHRS &ahrs, const Location &current_loc);
130  void Log_Write_ESC(void);
132  void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets);
133  void Log_Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets);
134  void Log_Write_Current();
135  void Log_Write_Compass(const Compass &compass, uint64_t time_us=0);
136  void Log_Write_Mode(uint8_t mode, uint8_t reason);
137 
138  void Log_Write_EntireMission(const AP_Mission &mission);
139  void Log_Write_Mission_Cmd(const AP_Mission &mission,
140  const AP_Mission::Mission_Command &cmd);
141  void Log_Write_Origin(uint8_t origin_type, const Location &loc);
142  void Log_Write_RPM(const AP_RPM &rpm_sensor);
143  void Log_Write_Rate(const AP_AHRS &ahrs,
144  const AP_Motors &motors,
145  const AC_AttitudeControl &attitude_control,
146  const AC_PosControl &pos_control);
147  void Log_Write_Rally(const AP_Rally &rally);
148  void Log_Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence);
149  void Log_Write_AOA_SSA(AP_AHRS &ahrs);
151  void Log_Write_Proximity(AP_Proximity &proximity);
152  void Log_Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& point);
153 
154  void Log_Write(const char *name, const char *labels, const char *fmt, ...);
155  void Log_Write(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...);
156  void Log_WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list);
157 
158  // This structure provides information on the internal member data of a PID for logging purposes
159  struct PID_Info {
160  float desired;
161  float P;
162  float I;
163  float D;
164  float FF;
165  float AFF;
166  };
167 
168  void Log_Write_PID(uint8_t msg_type, const PID_Info &info);
169 
170  // returns true if logging of a message should be attempted
171  bool should_log(uint32_t mask) const;
172 
173  bool logging_started(void);
174 
175 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
176  // currently only DataFlash_File support this:
177  void flush(void);
178 #endif
179 
180  void handle_mavlink_msg(class GCS_MAVLINK &, mavlink_message_t* msg);
181 
182  void periodic_tasks(); // may want to split this into GCS/non-GCS duties
183 
184  // number of blocks that have been dropped
185  uint32_t num_dropped(void) const;
186 
187  // accesss to public parameters
188  bool log_while_disarmed(void) const { return _params.log_disarmed != 0; }
189  uint8_t log_replay(void) const { return _params.log_replay; }
190 
191  vehicle_startup_message_Log_Writer _vehicle_messages;
192 
193  // parameter support
194  static const struct AP_Param::GroupInfo var_info[];
195  struct {
196  AP_Int8 backend_types;
197  AP_Int8 file_bufsize; // in kilobytes
199  AP_Int8 log_disarmed;
200  AP_Int8 log_replay;
201  AP_Int8 mav_bufsize; // in kilobytes
202  } _params;
203 
204  const struct LogStructure *structure(uint16_t num) const;
205  const struct UnitStructure *unit(uint16_t num) const;
206  const struct MultiplierStructure *multiplier(uint16_t num) const;
207 
208  // methods for mavlink SYS_STATUS message (send_extended_status1)
209  // these methods cover only the first logging backend used -
210  // typically DataFlash_File.
211  bool logging_present() const;
212  bool logging_enabled() const;
213  bool logging_failed() const;
214 
215  void set_vehicle_armed(bool armed_state);
216  bool vehicle_is_armed() const { return _armed; }
217 
218  void handle_log_send();
219  bool in_log_download() const { return _in_log_download; }
220 
221  float quiet_nanf() const { return nanf("0x4152"); } // "AR"
222  double quiet_nan() const { return nan("0x4152445550490a"); } // "ARDUPI"
223 
224 protected:
225 
226  const struct LogStructure *_structures;
227  uint8_t _num_types;
228  const struct UnitStructure *_units = log_Units;
230  const uint8_t _num_units = (sizeof(log_Units) / sizeof(log_Units[0]));
231  const uint8_t _num_multipliers = (sizeof(log_Multipliers) / sizeof(log_Multipliers[0]));
232 
233  /* Write a block with specified importance */
234  /* might be useful if you have a boolean indicating a message is
235  * important... */
236  void WritePrioritisedBlock(const void *pBuffer, uint16_t size,
237  bool is_critical);
238 
239 private:
240  #define DATAFLASH_MAX_BACKENDS 2
241  uint8_t _next_backend;
243  const char *_firmware_string;
244  const AP_Int32 &_log_bitmask;
245 
246  void internal_error() const;
247 
248  /*
249  * support for dynamic Log_Write; user-supplies name, format,
250  * labels and values in a single function call.
251  */
252 
253  // this structure looks much like struct LogStructure in
254  // LogStructure.h, however we need to remember a pointer value for
255  // efficiency of finding message types
256  struct log_write_fmt {
258  uint8_t msg_type;
259  uint8_t msg_len;
260  uint8_t sent_mask; // bitmask of backends sent to
261  const char *name;
262  const char *fmt;
263  const char *labels;
264  const char *units;
265  const char *mults;
266  } *log_write_fmts;
267 
268  // return (possibly allocating) a log_write_fmt for a name
269  struct log_write_fmt *msg_fmt_for_name(const char *name, const char *labels, const char *units, const char *mults, const char *fmt);
270 
271  // returns true if msg_type is associated with a message
272  bool msg_type_in_use(uint8_t msg_type) const;
273 
274  // return a msg_type which is not currently in use (or -1 if none available)
275  int16_t find_free_msg_type() const;
276 
277  // fill LogStructure with information about msg_type
278  bool fill_log_write_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const;
279 
280  // calculate the length of a message using fields specified in
281  // fmt; includes the message header
282  int16_t Log_Write_calc_msg_len(const char *fmt) const;
283 
284  bool _armed;
285 
286 #if AP_AHRS_NAVEKF_AVAILABLE
287  void Log_Write_EKF2(AP_AHRS_NavEKF &ahrs);
288  void Log_Write_EKF3(AP_AHRS_NavEKF &ahrs);
289 #endif
290 
291  void Log_Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type);
292  void Log_Write_IMU_instance(uint64_t time_us,
293  uint8_t imu_instance,
294  enum LogMessages type);
295  void Log_Write_Compass_instance(const Compass &compass,
296  uint64_t time_us,
297  uint8_t mag_instance,
298  enum LogMessages type);
299  void Log_Write_Current_instance(uint64_t time_us,
300  uint8_t battery_instance,
301  enum LogMessages type,
302  enum LogMessages celltype);
303  void Log_Write_IMUDT_instance(uint64_t time_us,
304  uint8_t imu_instance,
305  enum LogMessages type);
306 
307  void backend_starting_new_log(const DataFlash_Backend *backend);
308 
309 private:
311 
312 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
313  bool validate_structure(const struct LogStructure *logstructure, int16_t offset);
314  void validate_structures(const struct LogStructure *logstructures, const uint8_t num_types);
315  void dump_structure_field(const struct LogStructure *logstructure, const char *label, const uint8_t fieldnum);
316  void dump_structures(const struct LogStructure *logstructures, const uint8_t num_types);
318  const char *name,
319  const char *labels,
320  const char *units,
321  const char *mults,
322  const char *fmt) const;
323  const char* unit_name(const uint8_t unit_id);
324  double multiplier_name(const uint8_t multiplier_id);
325  bool seen_ids[256] = { };
326 #endif
327 
328  void Log_Write_EKF_Timing(const char *name, uint64_t time_us, const struct ekf_timing &timing);
329 
330  // possibly expensive calls to start log system:
331  void Prep();
332 
334 
335  /* support for retrieving logs via mavlink: */
336  uint8_t _log_listing:1; // sending log list
337  uint8_t _log_sending:1; // sending log data
338 
339  // bolean replicating old vehicle in_log_download flag:
341 
342  // next log list entry to send
344 
345  // last log list entry to send
347 
348  // number of log files
349  uint16_t _log_num_logs;
350 
351  // log number for data send
352  uint16_t _log_num_data;
353 
354  // offset in log
356 
357  // size of log file
358  uint32_t _log_data_size;
359 
360  // number of bytes left to send
362 
363  // start page of log data
364  uint16_t _log_data_page;
365 
367 
369  void handle_log_message(class GCS_MAVLINK &, mavlink_message_t *msg);
370 
371  void handle_log_request_list(class GCS_MAVLINK &, mavlink_message_t *msg);
372  void handle_log_request_data(class GCS_MAVLINK &, mavlink_message_t *msg);
373  void handle_log_request_erase(class GCS_MAVLINK &, mavlink_message_t *msg);
374  void handle_log_request_end(class GCS_MAVLINK &, mavlink_message_t *msg);
376  bool handle_log_send_data();
377 
378  void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
379 
380  int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
381 
382  /* end support for retrieving logs via mavlink: */
383 
384 };
float quiet_nanf() const
Definition: DataFlash.h:221
uint8_t log_replay(void) const
Definition: DataFlash.h:189
void handle_mavlink_msg(class GCS_MAVLINK &, mavlink_message_t *msg)
Definition: DataFlash.cpp:557
bool seen_ids[256]
Definition: DataFlash.h:325
void PrepForArming()
Definition: DataFlash.cpp:450
void Log_Write_MessageF(const char *fmt,...)
Definition: DataFlash.cpp:391
void dump_structure_field(const struct LogStructure *logstructure, const char *label, const uint8_t fieldnum)
pretty-print field information from a log structure
Definition: DataFlash.cpp:209
void Log_Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets)
Definition: LogFile.cpp:1378
static DataFlash_Class * _instance
Definition: DataFlash.h:310
void Log_Write_AOA_SSA(AP_AHRS &ahrs)
Definition: LogFile.cpp:1685
Object managing Rally Points.
Definition: AP_Rally.h:37
uint8_t _next_backend
Definition: DataFlash.h:241
uint16_t _log_next_list_entry
Definition: DataFlash.h:343
AP_Beacon beacon
int16_t find_free_msg_type() const
Definition: DataFlash.cpp:820
void Log_Write_Trigger(const AP_AHRS &ahrs, const Location &current_loc)
Definition: LogFile.cpp:1354
bool logging_enabled() const
Definition: DataFlash.cpp:365
struct log_write_fmt * next
Definition: DataFlash.h:257
struct log_write_fmt * msg_fmt_for_name(const char *name, const char *labels, const char *units, const char *mults, const char *fmt)
Definition: DataFlash.cpp:722
void Log_Write_Current()
Definition: LogFile.cpp:1436
const uint8_t _num_multipliers
Definition: DataFlash.h:231
void internal_error() const
Definition: DataFlash.cpp:625
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
uint8_t num_types() const
void Log_Write_Airspeed(AP_Airspeed &airspeed)
Definition: LogFile.cpp:1551
uint8_t _log_sending
Definition: DataFlash.h:337
bool logging_started(void)
Definition: DataFlash.cpp:548
Object managing Mission.
Definition: AP_Mission.h:45
bool should_log(uint32_t mask) const
Definition: DataFlash.cpp:416
FUNCTOR_TYPEDEF(vehicle_startup_message_Log_Writer, void)
void Log_Write_Beacon(AP_Beacon &beacon)
Definition: LogFile.cpp:1698
void Log_Write_Mode(uint8_t mode, uint8_t reason)
Definition: DataFlash.cpp:598
struct DataFlash_Class::@194 _params
const struct UnitStructure log_Units[]
Definition: LogStructure.h:81
void Log_Write_Rate(const AP_AHRS &ahrs, const AP_Motors &motors, const AC_AttitudeControl &attitude_control, const AC_PosControl &pos_control)
Definition: LogFile.cpp:1620
void Log_Write_Message(const char *message)
Definition: DataFlash.cpp:593
void Log_Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f &point)
Definition: LogFile.cpp:1762
void Log_Write_Proximity(AP_Proximity &proximity)
Definition: LogFile.cpp:1725
void Log_Write_Parameter(const char *name, float value)
Definition: DataFlash.cpp:603
void handle_log_message(class GCS_MAVLINK &, mavlink_message_t *msg)
#define DATAFLASH_MAX_BACKENDS
Definition: DataFlash.h:240
void WriteBlock(const void *pBuffer, uint16_t size)
Definition: DataFlash.cpp:481
void Log_Write_ESC(void)
Definition: LogFile.cpp:1509
void Log_Write_IMUDT(uint64_t time_us, uint8_t imu_mask)
Definition: LogFile.cpp:367
const struct LogStructure * structure(uint16_t num) const
Definition: DataFlash.cpp:356
void Log_Write_Radio(const mavlink_radio_t &packet)
Definition: LogFile.cpp:1296
void Log_Write_Compass_instance(const Compass &compass, uint64_t time_us, uint8_t mag_instance, enum LogMessages type)
Definition: LogFile.cpp:1455
DataFlash_Class & operator=(const DataFlash_Class &)=delete
void WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
Definition: DataFlash.cpp:489
const uint8_t _num_units
Definition: DataFlash.h:230
const struct MultiplierStructure log_Multipliers[]
Definition: LogStructure.h:123
const char * name
Definition: BusTest.cpp:11
AP_RSSI * rssi()
Definition: AP_RSSI.cpp:220
void Log_Write_PID(uint8_t msg_type, const PID_Info &info)
Definition: LogFile.cpp:1579
bool in_log_download() const
Definition: DataFlash.h:219
bool Log_Write_ISBH(uint16_t seqno, AP_InertialSensor::IMU_SENSOR_TYPE sensor_type, uint8_t instance, uint16_t multiplier, uint16_t sample_count, uint64_t sample_us, float sample_rate_hz)
Definition: DataFlash.cpp:919
void get_log_boundaries(uint16_t log_num, uint16_t &start_page, uint16_t &end_page)
Definition: DataFlash.cpp:522
AP_MotorsMatrix motors(400)
void backend_starting_new_log(const DataFlash_Backend *backend)
Definition: DataFlash.cpp:403
A system for managing and storing variables that are of general interest to the system.
Handles rally point storage and retrieval.
bool fill_log_write_logstructure(struct LogStructure &logstruct, const uint8_t msg_type) const
Definition: DataFlash.cpp:835
#define x(i)
uint16_t _log_last_list_entry
Definition: DataFlash.h:346
void set_vehicle_armed(bool armed_state)
Definition: DataFlash.cpp:460
void Log_Write_RSSI(AP_RSSI &rssi)
Definition: LogFile.cpp:248
void Log_Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence)
Definition: LogFile.cpp:1667
void Init(const struct LogStructure *structure, uint8_t num_types)
Definition: DataFlash.cpp:77
void dump_structures(const struct LogStructure *logstructures, const uint8_t num_types)
Definition: DataFlash.cpp:216
DataFlash_Backend_Type
Definition: DataFlash.h:37
AP_Int8 backend_types
Definition: DataFlash.h:196
void Log_Write_Compass(const Compass &compass, uint64_t time_us=0)
Definition: LogFile.cpp:1479
static const struct AP_Param::GroupInfo var_info[]
Definition: DataFlash.h:194
void Log_Write(const char *name, const char *labels, const char *fmt,...)
Definition: DataFlash.cpp:632
void Log_Write_IMU_instance(uint64_t time_us, uint8_t imu_instance, enum LogMessages type)
Definition: LogFile.cpp:294
void Log_Write_Rally(const AP_Rally &rally)
Definition: LogFile.cpp:1647
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)
Definition: DataFlash.cpp:534
void Log_Write_Camera(const AP_AHRS &ahrs, const Location &current_loc)
Definition: LogFile.cpp:1348
void Log_WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list)
Definition: DataFlash.cpp:650
#define f(i)
void Log_Write_POS(AP_AHRS &ahrs)
Definition: LogFile.cpp:485
const char * fmt
Definition: Printf.cpp:14
void validate_structures(const struct LogStructure *logstructures, const uint8_t num_types)
Definition: DataFlash.cpp:339
const struct MultiplierStructure * _multipliers
Definition: DataFlash.h:229
void set_mission(const AP_Mission *mission)
Definition: DataFlash.cpp:476
bool msg_type_in_use(uint8_t msg_type) const
Definition: DataFlash.cpp:799
double multiplier_name(const uint8_t multiplier_id)
return a multiplier value given its ID
Definition: DataFlash.cpp:197
const AP_Int32 & _log_bitmask
Definition: DataFlash.h:244
bool log_while_disarmed(void) const
Definition: DataFlash.h:188
AP_Int8 file_bufsize
Definition: DataFlash.h:197
void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets)
Definition: LogFile.cpp:1360
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
bool _in_log_download
Definition: DataFlash.h:340
Definition: AP_RPM.h:27
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
void handle_log_request_list(class GCS_MAVLINK &, mavlink_message_t *msg)
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc)
Definition: DataFlash.cpp:528
bool _writes_enabled
Definition: DataFlash.h:333
bool WritesEnabled() const
Definition: DataFlash.h:91
void Log_Write_Current_instance(uint64_t time_us, uint8_t battery_instance, enum LogMessages type, enum LogMessages celltype)
Definition: LogFile.cpp:1395
uint16_t _log_num_data
Definition: DataFlash.h:352
uint16_t find_last_log() const
Definition: DataFlash.cpp:516
AP_Int8 log_replay
Definition: DataFlash.h:200
void periodic_tasks()
Definition: DataFlash.cpp:575
const struct MultiplierStructure * multiplier(uint16_t num) const
Definition: DataFlash.cpp:438
void Log_Write_RCOUT(void)
Definition: LogFile.cpp:223
void Log_Write_AHRS2(AP_AHRS &ahrs)
Definition: LogFile.cpp:458
void setVehicle_Startup_Log_Writer(vehicle_startup_message_Log_Writer writer)
Definition: DataFlash.cpp:455
static Compass compass
Definition: AHRS_Test.cpp:20
bool validate_structure(const struct LogStructure *logstructure, int16_t offset)
Definition: DataFlash.cpp:245
bool logging_failed() const
Definition: DataFlash.cpp:377
void WriteCriticalBlock(const void *pBuffer, uint16_t size)
Definition: DataFlash.cpp:485
void Log_Write_Mission_Cmd(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd)
Definition: DataFlash.cpp:608
bool CardInserted(void)
Definition: DataFlash.cpp:498
void Log_Write_GPS(uint8_t instance, uint64_t time_us=0)
Definition: LogFile.cpp:136
bool logging_present() const
Definition: DataFlash.cpp:361
uint16_t _log_data_page
Definition: DataFlash.h:364
AP_Int32 log_bitmask
const struct UnitStructure * _units
Definition: DataFlash.h:228
const char * unit_name(const uint8_t unit_id)
return a unit name given its ID
Definition: DataFlash.cpp:186
void handle_log_request_data(class GCS_MAVLINK &, mavlink_message_t *msg)
Common definitions and utility routines for the ArduPilot libraries.
void Log_Write_RPM(const AP_RPM &rpm_sensor)
Definition: LogFile.cpp:1608
uint8_t _num_types
Definition: DataFlash.h:227
void handle_log_request_end(class GCS_MAVLINK &, mavlink_message_t *msg)
AP_Airspeed airspeed
Definition: Airspeed.cpp:34
void Log_Write_EKF_Timing(const char *name, uint64_t time_us, const struct ekf_timing &timing)
bool Log_Write_ISBD(uint16_t isb_seqno, uint16_t seqno, const int16_t x[32], const int16_t y[32], const int16_t z[32])
Definition: DataFlash.cpp:952
DataFlash_Class(const char *firmware_string, const AP_Int32 &log_bitmask)
Definition: DataFlash.cpp:65
void Log_Write_Power(void)
Definition: LogFile.cpp:437
void flush(void)
Definition: DataFlash.cpp:582
static uint16_t log_num
void Log_Write_Origin(uint8_t origin_type, const Location &loc)
Definition: LogFile.cpp:1594
AP_Int8 log_disarmed
Definition: DataFlash.h:199
void assert_same_fmt_for_name(const log_write_fmt *f, const char *name, const char *labels, const char *units, const char *mults, const char *fmt) const
Definition: DataFlash.cpp:676
void Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const Location &current_loc)
Definition: LogFile.cpp:1313
void EnableWrites(bool enable)
Definition: DataFlash.h:90
const struct UnitStructure * unit(uint16_t num) const
Definition: DataFlash.cpp:433
const char * _firmware_string
Definition: DataFlash.h:243
void StopLogging()
Definition: DataFlash.cpp:511
GCS_MAVLINK * _log_sending_link
Definition: DataFlash.h:366
float value
void Log_Write_EntireMission(const AP_Mission &mission)
Definition: DataFlash.cpp:588
uint32_t _log_data_offset
Definition: DataFlash.h:355
void handle_log_request_erase(class GCS_MAVLINK &, mavlink_message_t *msg)
void Log_Write_RFND(const RangeFinder &rangefinder)
Definition: LogFile.cpp:182
Catch-all header that defines all supported RangeFinder classes.
uint8_t _log_listing
Definition: DataFlash.h:336
void uint32_t num
Definition: systick.h:80
uint32_t _log_data_size
Definition: DataFlash.h:358
void Log_Write_IMUDT_instance(uint64_t time_us, uint8_t imu_instance, enum LogMessages type)
Definition: LogFile.cpp:341
void Log_Write_Vibration()
Definition: LogFile.cpp:390
vehicle_startup_message_Log_Writer _vehicle_messages
Definition: DataFlash.h:191
LogMessages
void Log_Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type)
Definition: LogFile.cpp:258
uint16_t _log_num_logs
Definition: DataFlash.h:349
const struct LogStructure * _structures
Definition: DataFlash.h:226
double quiet_nan() const
Definition: DataFlash.h:222
Vector2l point
Definition: polygon.cpp:34
void Log_Write_RCIN(void)
Definition: LogFile.cpp:199
bool Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t &mav_cmd)
uint32_t _log_data_remaining
Definition: DataFlash.h:361
AP_Int8 mav_bufsize
Definition: DataFlash.h:201
void Log_Write_Baro(uint64_t time_us=0)
Definition: LogFile.cpp:279
void Log_Write_IMU()
Definition: LogFile.cpp:320
int16_t Log_Write_calc_msg_len(const char *fmt) const
Definition: DataFlash.cpp:879
bool vehicle_is_armed() const
Definition: DataFlash.h:216
uint16_t get_num_logs(void)
Definition: DataFlash.cpp:540
uint32_t num_dropped(void) const
Definition: DataFlash.cpp:614
DataFlash_Backend * backends[DATAFLASH_MAX_BACKENDS]
Definition: DataFlash.h:242
struct DataFlash_Class::log_write_fmt * log_write_fmts
AP_Int8 file_disarm_rot
Definition: DataFlash.h:198