Skip to content
Snippets Groups Projects
Commit 234ec7f2 authored by Beat Küng's avatar Beat Küng
Browse files

logger: add mission log to frontend, configurable via SDLOG_MISSION

- mission logs are stored in a separate directory mission_log
- It's disabled by default
- Does not increase RAM usage if disabled (if enabled, only 300 bytes)
- Log rotate does not apply to the mission logs
parent 4fc1c5c4
No related branches found
No related tags found
No related merge requests found
......@@ -95,45 +95,45 @@ LogWriter::~LogWriter()
}
}
bool LogWriter::is_started() const
bool LogWriter::is_started(LogType type) const
{
bool ret = false;
if (_log_writer_file) {
ret = _log_writer_file->is_started(LogType::Full);
ret = _log_writer_file->is_started(type);
}
if (_log_writer_mavlink) {
if (_log_writer_mavlink && type == LogType::Full) {
ret = ret || _log_writer_mavlink->is_started();
}
return ret;
}
bool LogWriter::is_started(Backend query_backend) const
bool LogWriter::is_started(LogType type, Backend query_backend) const
{
if (query_backend == BackendFile && _log_writer_file) {
return _log_writer_file->is_started(LogType::Full);
return _log_writer_file->is_started(type);
}
if (query_backend == BackendMavlink && _log_writer_mavlink) {
if (query_backend == BackendMavlink && _log_writer_mavlink && type == LogType::Full) {
return _log_writer_mavlink->is_started();
}
return false;
}
void LogWriter::start_log_file(const char *filename)
void LogWriter::start_log_file(LogType type, const char *filename)
{
if (_log_writer_file) {
_log_writer_file->start_log(LogType::Full, filename);
_log_writer_file->start_log(type, filename);
}
}
void LogWriter::stop_log_file()
void LogWriter::stop_log_file(LogType type)
{
if (_log_writer_file) {
_log_writer_file->stop_log(LogType::Full);
_log_writer_file->stop_log(type);
}
}
......@@ -158,15 +158,15 @@ void LogWriter::thread_stop()
}
}
int LogWriter::write_message(void *ptr, size_t size, uint64_t dropout_start)
int LogWriter::write_message(LogType type, void *ptr, size_t size, uint64_t dropout_start)
{
int ret_file = 0, ret_mavlink = 0;
if (_log_writer_file_for_write) {
ret_file = _log_writer_file_for_write->write_message(LogType::Full, ptr, size, dropout_start);
ret_file = _log_writer_file_for_write->write_message(type, ptr, size, dropout_start);
}
if (_log_writer_mavlink_for_write) {
if (_log_writer_mavlink_for_write && type == LogType::Full) {
ret_mavlink = _log_writer_mavlink_for_write->write_message(ptr, size);
}
......
......@@ -65,9 +65,9 @@ public:
/** stop all running threads and wait for them to exit */
void thread_stop();
void start_log_file(const char *filename);
void start_log_file(LogType type, const char *filename);
void stop_log_file();
void stop_log_file(LogType type);
void start_log_mavlink();
......@@ -76,20 +76,21 @@ public:
/**
* whether logging is currently active or not (any of the selected backends).
*/
bool is_started() const;
bool is_started(LogType type) const;
/**
* whether logging is currently active or not for a specific backend.
*/
bool is_started(Backend query_backend) const;
bool is_started(LogType type, Backend query_backend) const;
/**
* Write a single ulog message (including header). The caller must call lock() before calling this.
* @param dropout_start timestamp when lastest dropout occured. 0 if no dropout at the moment.
* @return 0 on success (or if no logging started),
* -1 if not enough space in the buffer left (file backend), -2 mavlink backend failed
* add type -> pass through, but not to mavlink if mission log
*/
int write_message(void *ptr, size_t size, uint64_t dropout_start = 0);
int write_message(LogType type, void *ptr, size_t size, uint64_t dropout_start = 0);
/**
* Select a backend, so that future calls to write_message() only write to the selected
......@@ -116,23 +117,23 @@ public:
if (_log_writer_file) { _log_writer_file->notify(); }
}
size_t get_total_written_file() const
size_t get_total_written_file(LogType type) const
{
if (_log_writer_file) { return _log_writer_file->get_total_written(LogType::Full); }
if (_log_writer_file) { return _log_writer_file->get_total_written(type); }
return 0;
}
size_t get_buffer_size_file() const
size_t get_buffer_size_file(LogType type) const
{
if (_log_writer_file) { return _log_writer_file->get_buffer_size(LogType::Full); }
if (_log_writer_file) { return _log_writer_file->get_buffer_size(type); }
return 0;
}
size_t get_buffer_fill_count_file() const
size_t get_buffer_fill_count_file(LogType type) const
{
if (_log_writer_file) { return _log_writer_file->get_buffer_fill_count(LogType::Full); }
if (_log_writer_file) { return _log_writer_file->get_buffer_fill_count(type); }
return 0;
}
......
This diff is collapsed.
......@@ -64,7 +64,13 @@ enum class SDLogProfileMask : int32_t {
SYSTEM_IDENTIFICATION = 1 << 3,
HIGH_RATE = 1 << 4,
DEBUG_TOPICS = 1 << 5,
SENSOR_COMPARISON = 1 << 6
SENSOR_COMPARISON = 1 << 6
};
enum class MissionLogType : int32_t {
Disabled = 0,
Complete = 1,
Geotagging = 2
};
inline bool operator&(SDLogProfileMask a, SDLogProfileMask b)
......@@ -151,7 +157,7 @@ public:
*/
static bool request_stop_static();
void print_statistics();
void print_statistics(LogType type);
void set_arm_override(bool override) { _arm_override = override; }
......@@ -164,35 +170,62 @@ private:
};
static constexpr size_t MAX_TOPICS_NUM = 64; /**< Maximum number of logged topics */
static constexpr int MAX_MISSION_TOPICS_NUM = 5; /**< Maximum number of mission topics */
static constexpr unsigned MAX_NO_LOGFILE = 999; /**< Maximum number of log files */
static constexpr const char *LOG_ROOT = PX4_STORAGEDIR "/log";
static constexpr const char *LOG_ROOT[(int)LogType::Count] = {
PX4_STORAGEDIR "/log",
PX4_STORAGEDIR "/mission_log"
};
struct LogFileName {
char log_dir[12]; ///< e.g. "2018-01-01" or "sess001"
int sess_dir_index{1}; ///< search starting index for 'sess<i>' directory name
char log_file_name[31]; ///< e.g. "log001.ulg" or "12_09_00_replayed.ulg"
bool has_log_dir{false};
};
struct Statistics {
hrt_abstime start_time_file{0}; ///< Time when logging started, file backend (not the logger thread)
hrt_abstime dropout_start{0}; ///< start of current dropout (0 = no dropout)
float max_dropout_duration{0.0f}; ///< max duration of dropout [s]
size_t write_dropouts{0}; ///< failed buffer writes due to buffer overflow
size_t high_water{0}; ///< maximum used write buffer
};
struct MissionSubscription {
unsigned min_delta_ms; ///< minimum time between 2 topic writes [ms]
unsigned next_write_time; ///< next time to write in 0.1 seconds
};
/**
* Write an ADD_LOGGED_MSG to the log for a all current subscriptions and instances
*/
void write_all_add_logged_msg();
void write_all_add_logged_msg(LogType type);
/**
* Write an ADD_LOGGED_MSG to the log for a given subscription and instance.
* _writer.lock() must be held when calling this.
*/
void write_add_logged_msg(LoggerSubscription &subscription, int instance);
void write_add_logged_msg(LogType type, LoggerSubscription &subscription, int instance);
/**
* Create logging directory
* @param type
* @param tt if not null, use it for the directory name
* @return 0 on success
* @param log_dir returned log directory path
* @param log_dir_len log_dir buffer length
* @return string length of log_dir (excluding terminating null-char), <0 on error
*/
int create_log_dir(tm *tt);
int create_log_dir(LogType type, tm *tt, char *log_dir, int log_dir_len);
/**
* Get log file name with directory (create it if necessary)
*/
int get_log_file_name(char *file_name, size_t file_name_size);
int get_log_file_name(LogType type, char *file_name, size_t file_name_size);
void start_log_file();
void start_log_file(LogType type);
void stop_log_file();
void stop_log_file(LogType type);
void start_log_mavlink();
......@@ -201,7 +234,8 @@ private:
/** check if mavlink logging can be started */
bool can_start_mavlink_log() const
{
return !_writer.is_started(LogWriter::BackendMavlink) && (_writer.backend() & LogWriter::BackendMavlink) != 0;
return !_writer.is_started(LogType::Full, LogWriter::BackendMavlink)
&& (_writer.backend() & LogWriter::BackendMavlink) != 0;
}
/** get the configured backend as string */
......@@ -210,13 +244,14 @@ private:
/**
* write the file header with file magic and timestamp.
*/
void write_header();
void write_header(LogType type);
/// Array to store written formats (add some more for nested definitions)
using WrittenFormats = Array < const orb_metadata *, MAX_TOPICS_NUM + 10 >;
void write_format(const orb_metadata &meta, WrittenFormats &written_formats, ulog_message_format_s &msg, int level = 1);
void write_formats();
void write_format(LogType type, const orb_metadata &meta, WrittenFormats &written_formats, ulog_message_format_s &msg,
int level = 1);
void write_formats(LogType type);
/**
* write performance counters
......@@ -234,22 +269,22 @@ private:
*/
static void print_load_callback(void *user);
void write_version();
void write_version(LogType type);
void write_info(const char *name, const char *value);
void write_info_multiple(const char *name, const char *value, bool is_continued);
void write_info(const char *name, int32_t value);
void write_info(const char *name, uint32_t value);
void write_info(LogType type, const char *name, const char *value);
void write_info_multiple(LogType type, const char *name, const char *value, bool is_continued);
void write_info(LogType type, const char *name, int32_t value);
void write_info(LogType type, const char *name, uint32_t value);
/** generic common template method for write_info variants */
template<typename T>
void write_info_template(const char *name, T value, const char *type_str);
void write_info_template(LogType type, const char *name, T value, const char *type_str);
void write_parameters();
void write_parameters(LogType type);
void write_changed_parameters();
void write_changed_parameters(LogType type);
inline bool copy_if_updated_multi(LoggerSubscription &sub, int multi_instance, void *buffer, bool try_to_subscribe);
inline bool copy_if_updated_multi(int sub_idx, int multi_instance, void *buffer, bool try_to_subscribe);
/**
* Check if a topic instance exists and subscribe to it
......@@ -262,7 +297,7 @@ private:
* Must be called with _writer.lock() held.
* @return true if data written, false otherwise (on overflow)
*/
bool write_message(void *ptr, size_t size);
bool write_message(LogType type, void *ptr, size_t size);
/**
* Parse a file containing a list of uORB topics to log, calling add_topic for each
......@@ -271,6 +306,20 @@ private:
*/
int add_topics_from_file(const char *fname);
/**
* Add topic subscriptions based on the configured mission log type
*/
void initialize_mission_topics(MissionLogType type);
/**
* Add a topic to be logged for the mission log (it's also added to the full log).
* The interval is expected to be 0 or large (in the order of 0.1 seconds or higher).
* Must be called before all other topics are added.
* @param name topic name
* @param interval limit rate if >0 [ms], otherwise log as fast as the topic is updated.
*/
void add_mission_topic(const char *name, unsigned interval = 0);
/**
* Add topic subscriptions based on the _sdlog_profile_handle parameter
*/
......@@ -287,9 +336,10 @@ private:
/**
* check current arming state and start/stop logging if state changed and according to configured params.
* @param vehicle_status_sub
* @param mission_log_type
* @return true if log started
*/
bool check_arming_state(int vehicle_status_sub);
bool check_arming_state(int vehicle_status_sub, MissionLogType mission_log_type);
void handle_vehicle_command_update(int vehicle_command_sub, orb_advert_t &vehicle_command_ack_pub);
void ack_vehicle_command(orb_advert_t &vehicle_command_ack_pub, vehicle_command_s *cmd, uint32_t result);
......@@ -307,25 +357,22 @@ private:
uint8_t *_msg_buffer{nullptr};
int _msg_buffer_len{0};
char _log_dir[LOG_DIR_LEN] {};
int _sess_dir_index{1}; ///< search starting index for 'sess<i>' directory name
char _log_file_name[32];
bool _has_log_dir{false};
LogFileName _file_name[(int)LogType::Count];
bool _was_armed{false};
bool _arm_override{false};
// statistics
hrt_abstime _start_time_file{0}; ///< Time when logging started, file backend (not the logger thread)
hrt_abstime _dropout_start{0}; ///< start of current dropout (0 = no dropout)
float _max_dropout_duration{0.0f}; ///< max duration of dropout [s]
size_t _write_dropouts{0}; ///< failed buffer writes due to buffer overflow
size_t _high_water{0}; ///< maximum used write buffer
Statistics _statistics[(int)LogType::Count];
const bool _log_on_start;
const bool _log_until_shutdown;
const bool _log_name_timestamp;
Array<LoggerSubscription, MAX_TOPICS_NUM> _subscriptions;
Array<LoggerSubscription, MAX_TOPICS_NUM> _subscriptions; ///< all subscriptions for full & mission log (in front)
MissionSubscription _mission_subscriptions[MAX_MISSION_TOPICS_NUM]; ///< additional data for mission subscriptions
int _num_mission_subs{0};
LogWriter _writer;
uint32_t _log_interval{0};
const orb_metadata *_polling_topic_meta{nullptr}; ///< if non-null, poll on this topic instead of sleeping
......@@ -333,15 +380,15 @@ private:
uint8_t _next_topic_id{0}; ///< id of next subscribed ulog topic
char *_replay_file_name{nullptr};
bool _should_stop_file_log{false}; /**< if true _next_load_print is set and file logging
will be stopped after load printing */
will be stopped after load printing (for the full log) */
print_load_s _load{}; ///< process load data
hrt_abstime _next_load_print{0}; ///< timestamp when to print the process load
PrintLoadReason _print_load_reason;
// control
param_t _sdlog_profile_handle{PARAM_INVALID};
param_t _log_utc_offset{PARAM_INVALID};
param_t _log_dirs_max{PARAM_INVALID};
param_t _mission_log{PARAM_INVALID};
};
} //namespace logger
......
......@@ -59,13 +59,35 @@ PARAM_DEFINE_INT32(SDLOG_UTC_OFFSET, 0);
* @value 1 from boot until disarm
* @value 2 from boot until shutdown
*
* @min 0
* @max 2
* @reboot_required true
* @group SD Logging
*/
PARAM_DEFINE_INT32(SDLOG_MODE, 0);
/**
* Mission Log
*
* If enabled, a second mission log file will be written to the SD card.
* This is a small log file with reduced information content (such as the
* vehicle position) that for example can be used for flight statistics,
* regulatory purposes or geotagging.
*
* The normal full log file will still be generated and it contains all
* the data that a mission log contains.
*
* The different modes can be used to further reduce the amount of logged data
* and thus the log file size. Geotagging for instance will only log data
* required for geotagging.
*
* @value 0 Disabled
* @value 1 Complete
* @value 2 Geotagging
*
* @reboot_required true
* @group SD Logging
*/
PARAM_DEFINE_INT32(SDLOG_MISSION, 0);
/**
* Logging topic profile (integer bitmask).
*
......@@ -111,6 +133,8 @@ PARAM_DEFINE_INT32(SDLOG_PROFILE, 3);
* If this is set to 0, old directories will only be removed if the free space falls below
* the minimum.
*
* Note: this does not apply to mission log files.
*
* @min 0
* @max 1000
* @reboot_required true
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment