PX4 Firmware
PX4 Autopilot Software http://px4.io
logger.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2016 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 #pragma once
35 
36 #include "log_writer.h"
37 #include "messages.h"
38 #include <containers/Array.hpp>
39 #include "util.h"
40 #include <px4_platform_common/defines.h>
41 #include <drivers/drv_hrt.h>
42 #include <version/version.h>
43 #include <parameters/param.h>
44 #include <systemlib/printload.h>
45 #include <px4_platform_common/module.h>
46 
47 #include <uORB/Subscription.hpp>
53 
54 extern "C" __EXPORT int logger_main(int argc, char *argv[]);
55 
56 static constexpr hrt_abstime TRY_SUBSCRIBE_INTERVAL{1000 * 1000}; // interval in microseconds at which we try to subscribe to a topic
57 // if we haven't succeeded before
58 
59 namespace px4
60 {
61 namespace logger
62 {
63 
64 enum class SDLogProfileMask : int32_t {
65  DEFAULT = 1 << 0,
66  ESTIMATOR_REPLAY = 1 << 1,
67  THERMAL_CALIBRATION = 1 << 2,
68  SYSTEM_IDENTIFICATION = 1 << 3,
69  HIGH_RATE = 1 << 4,
70  DEBUG_TOPICS = 1 << 5,
71  SENSOR_COMPARISON = 1 << 6,
72  VISION_AND_AVOIDANCE = 1 << 7
73 };
74 
75 enum class MissionLogType : int32_t {
76  Disabled = 0,
77  Complete = 1,
78  Geotagging = 2
79 };
80 
82 {
83  return static_cast<int32_t>(a) & static_cast<int32_t>(b);
84 }
85 
86 static constexpr uint8_t MSG_ID_INVALID = UINT8_MAX;
87 
89 
90  uint8_t msg_id{MSG_ID_INVALID};
91 
92  LoggerSubscription() = default;
93 
94  LoggerSubscription(const orb_metadata *meta, uint32_t interval_ms = 0, uint8_t instance = 0) :
95  uORB::SubscriptionInterval(meta, interval_ms * 1000, instance)
96  {}
97 };
98 
99 class Logger : public ModuleBase<Logger>
100 {
101 public:
102  enum class LogMode {
103  while_armed = 0,
104  boot_until_disarm,
105  boot_until_shutdown,
106  rc_aux1
107  };
108 
109  Logger(LogWriter::Backend backend, size_t buffer_size, uint32_t log_interval, const char *poll_topic_name,
110  LogMode log_mode, bool log_name_timestamp);
111 
112  ~Logger();
113 
114  /** @see ModuleBase */
115  static int task_spawn(int argc, char *argv[]);
116 
117  /** @see ModuleBase */
118  static Logger *instantiate(int argc, char *argv[]);
119 
120  /** @see ModuleBase */
121  static int custom_command(int argc, char *argv[]);
122 
123  /** @see ModuleBase */
124  static int print_usage(const char *reason = nullptr);
125 
126  /** @see ModuleBase::run() */
127  void run() override;
128 
129  /** @see ModuleBase::print_status() */
130  int print_status() override;
131 
132  /**
133  * Tell the logger that we're in replay mode. This must be called
134  * before starting the logger.
135  * @param file_name file name of the used log replay file. Will be copied.
136  */
137  void setReplayFile(const char *file_name);
138 
139  /**
140  * Add a topic to be logged. This must be called before start_log()
141  * (because it does not write an ADD_LOGGED_MSG message).
142  * @param name topic name
143  * @param interval limit in milliseconds if >0, otherwise log as fast as the topic is updated.
144  * @param instance orb topic instance
145  * @return true on success
146  */
147  bool add_topic(const char *name, uint32_t interval_ms = 0, uint8_t instance = 0);
148  bool add_topic_multi(const char *name, uint32_t interval_ms = 0);
149 
150  /**
151  * add a logged topic (called by add_topic() above).
152  * In addition, it subscribes to the first instance of the topic, if it's advertised,
153  * @return the newly added subscription on success, nullptr otherwise
154  */
155  LoggerSubscription *add_topic(const orb_metadata *topic, uint32_t interval_ms = 0, uint8_t instance = 0);
156 
157  /**
158  * request the logger thread to stop (this method does not block).
159  * @return true if the logger is stopped, false if (still) running
160  */
161  static bool request_stop_static();
162 
163  void print_statistics(LogType type);
164 
165  void set_arm_override(bool override) { _manually_logging_override = override; }
166 
167 private:
168 
169  enum class PrintLoadReason {
170  Preflight,
171  Postflight,
172  Watchdog
173  };
174 
175  static constexpr size_t MAX_TOPICS_NUM = 90; /**< Maximum number of logged topics */
176  static constexpr int MAX_MISSION_TOPICS_NUM = 5; /**< Maximum number of mission topics */
177  static constexpr unsigned MAX_NO_LOGFILE = 999; /**< Maximum number of log files */
178  static constexpr const char *LOG_ROOT[(int)LogType::Count] = {
179  PX4_STORAGEDIR "/log",
180  PX4_STORAGEDIR "/mission_log"
181  };
182 
183  struct LogFileName {
184  char log_dir[12]; ///< e.g. "2018-01-01" or "sess001"
185  int sess_dir_index{1}; ///< search starting index for 'sess<i>' directory name
186  char log_file_name[31]; ///< e.g. "log001.ulg" or "12_09_00_replayed.ulg"
187  bool has_log_dir{false};
188  };
189 
190  struct Statistics {
191  hrt_abstime start_time_file{0}; ///< Time when logging started, file backend (not the logger thread)
192  hrt_abstime dropout_start{0}; ///< start of current dropout (0 = no dropout)
193  float max_dropout_duration{0.0f}; ///< max duration of dropout [s]
194  size_t write_dropouts{0}; ///< failed buffer writes due to buffer overflow
195  size_t high_water{0}; ///< maximum used write buffer
196  };
197 
199  unsigned min_delta_ms{0}; ///< minimum time between 2 topic writes [ms]
200  unsigned next_write_time{0}; ///< next time to write in 0.1 seconds
201  };
202 
203  /**
204  * Write an ADD_LOGGED_MSG to the log for a all current subscriptions and instances
205  */
206  void write_all_add_logged_msg(LogType type);
207 
208  /**
209  * Write an ADD_LOGGED_MSG to the log for a given subscription and instance.
210  * _writer.lock() must be held when calling this.
211  */
212  void write_add_logged_msg(LogType type, LoggerSubscription &subscription);
213 
214  /**
215  * Create logging directory
216  * @param type
217  * @param tt if not null, use it for the directory name
218  * @param log_dir returned log directory path
219  * @param log_dir_len log_dir buffer length
220  * @return string length of log_dir (excluding terminating null-char), <0 on error
221  */
222  int create_log_dir(LogType type, tm *tt, char *log_dir, int log_dir_len);
223 
224  /**
225  * Get log file name with directory (create it if necessary)
226  */
227  int get_log_file_name(LogType type, char *file_name, size_t file_name_size);
228 
229  void start_log_file(LogType type);
230 
231  void stop_log_file(LogType type);
232 
233  void start_log_mavlink();
234 
235  void stop_log_mavlink();
236 
237  /** check if mavlink logging can be started */
239  {
240  return !_writer.is_started(LogType::Full, LogWriter::BackendMavlink)
241  && (_writer.backend() & LogWriter::BackendMavlink) != 0;
242  }
243 
244  /** get the configured backend as string */
245  const char *configured_backend_mode() const;
246 
247  /**
248  * write the file header with file magic and timestamp.
249  */
250  void write_header(LogType type);
251 
252  /// Array to store written formats (add some more for nested definitions)
254 
255  void write_format(LogType type, const orb_metadata &meta, WrittenFormats &written_formats, ulog_message_format_s &msg,
256  int level = 1);
257  void write_formats(LogType type);
258 
259  /**
260  * write performance counters
261  * @param preflight preflight if true, postflight otherwise
262  */
263  void write_perf_data(bool preflight);
264 
265  /**
266  * write bootup console output
267  */
268  void write_console_output();
269 
270  /**
271  * callback to write the performance counters
272  */
273  static void perf_iterate_callback(perf_counter_t handle, void *user);
274 
275  /**
276  * callback for print_load_buffer() to print the process load
277  */
278  static void print_load_callback(void *user);
279 
280  void write_version(LogType type);
281 
282  void write_info(LogType type, const char *name, const char *value);
283  void write_info_multiple(LogType type, const char *name, const char *value, bool is_continued);
284  void write_info(LogType type, const char *name, int32_t value);
285  void write_info(LogType type, const char *name, uint32_t value);
286 
287  /** generic common template method for write_info variants */
288  template<typename T>
289  void write_info_template(LogType type, const char *name, T value, const char *type_str);
290 
291  void write_parameters(LogType type);
292 
293  void write_changed_parameters(LogType type);
294 
295  inline bool copy_if_updated(int sub_idx, void *buffer, bool try_to_subscribe);
296 
297  /**
298  * Write exactly one ulog message to the logger and handle dropouts.
299  * Must be called with _writer.lock() held.
300  * @return true if data written, false otherwise (on overflow)
301  */
302  bool write_message(LogType type, void *ptr, size_t size);
303 
304  /**
305  * Parse a file containing a list of uORB topics to log, calling add_topic for each
306  * @param fname name of file
307  * @return number of topics added
308  */
309  int add_topics_from_file(const char *fname);
310 
311  /**
312  * Add topic subscriptions based on the configured mission log type
313  */
314  void initialize_mission_topics(MissionLogType type);
315 
316  /**
317  * Add a topic to be logged for the mission log (it's also added to the full log).
318  * The interval is expected to be 0 or large (in the order of 0.1 seconds or higher).
319  * Must be called before all other topics are added.
320  * @param name topic name
321  * @param interval limit rate if >0 [ms], otherwise log as fast as the topic is updated.
322  */
323  void add_mission_topic(const char *name, uint32_t interval_ms = 0);
324 
325  /**
326  * Add topic subscriptions based on the _sdlog_profile_handle parameter
327  */
328  void initialize_configured_topics();
329 
330  void add_default_topics();
331  void add_estimator_replay_topics();
332  void add_thermal_calibration_topics();
333  void add_system_identification_topics();
334  void add_high_rate_topics();
335  void add_debug_topics();
336  void add_sensor_comparison_topics();
337  void add_vision_and_avoidance_topics();
338 
339  /**
340  * check current arming state or aux channel and start/stop logging if state changed and according to
341  * configured params.
342  * @param vehicle_status_sub
343  * @param manual_control_sp_sub
344  * @param mission_log_type
345  * @return true if log started
346  */
347  bool start_stop_logging(MissionLogType mission_log_type);
348 
349  void handle_vehicle_command_update();
350  void ack_vehicle_command(vehicle_command_s *cmd, uint32_t result);
351 
352  /**
353  * initialize the output for the process load, so that ~1 second later it will be written to the log
354  */
355  void initialize_load_output(PrintLoadReason reason);
356 
357  /**
358  * write the process load, which was previously initialized with initialize_load_output()
359  */
360  void write_load_output();
361 
362  /**
363  * Regularly print the buffer fill state (only if DBGPRINT is set)
364  * @param total_bytes total written bytes (to the full file), will be reset on each print
365  * @param timer_start time since last print
366  */
367  inline void debug_print_buffer(uint32_t &total_bytes, hrt_abstime &timer_start);
368 
369 
370  uint8_t *_msg_buffer{nullptr};
371  int _msg_buffer_len{0};
372 
373  LogFileName _file_name[(int)LogType::Count];
374 
375  bool _prev_state{false}; ///< previous state depending on logging mode (arming or aux1 state)
376  bool _manually_logging_override{false};
377 
378  Statistics _statistics[(int)LogType::Count];
379  hrt_abstime _last_sync_time{0}; ///< last time a sync msg was sent
380 
383 
384  Array<LoggerSubscription, MAX_TOPICS_NUM> _subscriptions; ///< all subscriptions for full & mission log (in front)
385  MissionSubscription _mission_subscriptions[MAX_MISSION_TOPICS_NUM] {}; ///< additional data for mission subscriptions
386  int _num_mission_subs{0};
387 
389  uint32_t _log_interval{0};
390  const orb_metadata *_polling_topic_meta{nullptr}; ///< if non-null, poll on this topic instead of sleeping
391  orb_advert_t _mavlink_log_pub{nullptr};
392  uint8_t _next_topic_id{0}; ///< id of next subscribed ulog topic
393  char *_replay_file_name{nullptr};
394  bool _should_stop_file_log{false}; /**< if true _next_load_print is set and file logging
395  will be stopped after load printing (for the full log) */
396  print_load_s _load{}; ///< process load data
397  hrt_abstime _next_load_print{0}; ///< timestamp when to print the process load
398  PrintLoadReason _print_load_reason {PrintLoadReason::Preflight};
399 
400  uORB::Subscription _manual_control_sp_sub{ORB_ID(manual_control_setpoint)};
401  uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)};
402  uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
403  uORB::SubscriptionInterval _log_message_sub{ORB_ID(log_message), 20};
404 
405  param_t _sdlog_profile_handle{PARAM_INVALID};
406  param_t _log_utc_offset{PARAM_INVALID};
407  param_t _log_dirs_max{PARAM_INVALID};
408  param_t _mission_log{PARAM_INVALID};
409 };
410 
411 } //namespace logger
412 } //namespace px4
#define PARAM_INVALID
Handle returned when a parameter cannot be found.
Definition: param.h:103
SDLogProfileMask
Definition: logger.h:64
void set_arm_override(bool override)
Definition: logger.h:165
uint8_t Backend
bitfield to specify a backend
Definition: log_writer.h:53
Manages starting, stopping & writing of logged data using the configured backend. ...
Definition: log_writer.h:48
static constexpr uint8_t MSG_ID_INVALID
Definition: logger.h:86
const bool _log_name_timestamp
Definition: logger.h:382
LogType
Defines different log (file) types.
Definition: I2C.hpp:51
void print_status()
Definition: Commander.cpp:517
MissionLogType
Definition: logger.h:75
static void print_usage()
LidarLite * instance
Definition: ll40ls.cpp:65
High-resolution timer with callouts and timekeeping.
Global flash based parameter store.
__EXPORT int logger_main(int argc, char *argv[])
Definition: logger.cpp:117
static char msg[NUM_MSG][CONFIG_USART1_TXBUFSIZE]
Definition: px4io.c:89
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
Print the current system load.
Array< LoggerSubscription, MAX_TOPICS_NUM > _subscriptions
all subscriptions for full & mission log (in front)
Definition: logger.h:384
Header common to all counters.
bool can_start_mavlink_log() const
check if mavlink logging can be started
Definition: logger.h:238
Normal, full size log.
LogMode _log_mode
Definition: logger.h:381
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
Tools for system version detection.
const char * name
Definition: tests_main.c:58
Object metadata.
Definition: uORB.h:50
LogWriter _writer
Definition: logger.h:388
static enum @84 backend
Definition: bst.cpp:62
static constexpr hrt_abstime TRY_SUBSCRIBE_INTERVAL
Definition: logger.h:56
bool operator &(SDLogProfileMask a, SDLogProfileMask b)
Definition: logger.h:81
LoggerSubscription(const orb_metadata *meta, uint32_t interval_ms=0, uint8_t instance=0)
Definition: logger.h:94
static constexpr Backend BackendMavlink
Definition: log_writer.h:55
uint32_t param_t
Parameter handle.
Definition: param.h:98