PX4 Firmware
PX4 Autopilot Software http://px4.io
px4::logger::Logger Class Reference

#include <logger.h>

Inheritance diagram for px4::logger::Logger:
Collaboration diagram for px4::logger::Logger:

Classes

struct  LogFileName
 
struct  MissionSubscription
 
struct  Statistics
 

Public Types

enum  LogMode { LogMode::while_armed = 0, LogMode::boot_until_disarm, LogMode::boot_until_shutdown, LogMode::rc_aux1 }
 

Public Member Functions

 Logger (LogWriter::Backend backend, size_t buffer_size, uint32_t log_interval, const char *poll_topic_name, LogMode log_mode, bool log_name_timestamp)
 
 ~Logger ()
 
void run () override
 
int print_status () override
 
void setReplayFile (const char *file_name)
 Tell the logger that we're in replay mode. More...
 
bool add_topic (const char *name, uint32_t interval_ms=0, uint8_t instance=0)
 Add a topic to be logged. More...
 
bool add_topic_multi (const char *name, uint32_t interval_ms=0)
 
LoggerSubscriptionadd_topic (const orb_metadata *topic, uint32_t interval_ms=0, uint8_t instance=0)
 add a logged topic (called by add_topic() above). More...
 
void print_statistics (LogType type)
 
void set_arm_override (bool override)
 

Static Public Member Functions

static int task_spawn (int argc, char *argv[])
 
static Loggerinstantiate (int argc, char *argv[])
 
static int custom_command (int argc, char *argv[])
 
static int print_usage (const char *reason=nullptr)
 
static bool request_stop_static ()
 request the logger thread to stop (this method does not block). More...
 

Private Types

enum  PrintLoadReason { PrintLoadReason::Preflight, PrintLoadReason::Postflight, PrintLoadReason::Watchdog }
 
using WrittenFormats = Array< const orb_metadata *, MAX_TOPICS_NUM+10 >
 Array to store written formats (add some more for nested definitions) More...
 

Private Member Functions

void write_all_add_logged_msg (LogType type)
 Write an ADD_LOGGED_MSG to the log for a all current subscriptions and instances. More...
 
void write_add_logged_msg (LogType type, LoggerSubscription &subscription)
 Write an ADD_LOGGED_MSG to the log for a given subscription and instance. More...
 
int create_log_dir (LogType type, tm *tt, char *log_dir, int log_dir_len)
 Create logging directory. More...
 
int get_log_file_name (LogType type, char *file_name, size_t file_name_size)
 Get log file name with directory (create it if necessary) More...
 
void start_log_file (LogType type)
 
void stop_log_file (LogType type)
 
void start_log_mavlink ()
 
void stop_log_mavlink ()
 
bool can_start_mavlink_log () const
 check if mavlink logging can be started More...
 
const char * configured_backend_mode () const
 get the configured backend as string More...
 
void write_header (LogType type)
 write the file header with file magic and timestamp. More...
 
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)
 
void write_perf_data (bool preflight)
 write performance counters More...
 
void write_console_output ()
 write bootup console output More...
 
void write_version (LogType type)
 
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)
 
template<typename T >
void write_info_template (LogType type, const char *name, T value, const char *type_str)
 generic common template method for write_info variants More...
 
void write_parameters (LogType type)
 
void write_changed_parameters (LogType type)
 
bool copy_if_updated (int sub_idx, void *buffer, bool try_to_subscribe)
 
bool write_message (LogType type, void *ptr, size_t size)
 Write exactly one ulog message to the logger and handle dropouts. More...
 
int add_topics_from_file (const char *fname)
 Parse a file containing a list of uORB topics to log, calling add_topic for each. More...
 
void initialize_mission_topics (MissionLogType type)
 Add topic subscriptions based on the configured mission log type. More...
 
void add_mission_topic (const char *name, uint32_t interval_ms=0)
 Add a topic to be logged for the mission log (it's also added to the full log). More...
 
void initialize_configured_topics ()
 Add topic subscriptions based on the _sdlog_profile_handle parameter. More...
 
void add_default_topics ()
 
void add_estimator_replay_topics ()
 
void add_thermal_calibration_topics ()
 
void add_system_identification_topics ()
 
void add_high_rate_topics ()
 
void add_debug_topics ()
 
void add_sensor_comparison_topics ()
 
void add_vision_and_avoidance_topics ()
 
bool start_stop_logging (MissionLogType mission_log_type)
 check current arming state or aux channel and start/stop logging if state changed and according to configured params. More...
 
void handle_vehicle_command_update ()
 
void ack_vehicle_command (vehicle_command_s *cmd, uint32_t result)
 
void initialize_load_output (PrintLoadReason reason)
 initialize the output for the process load, so that ~1 second later it will be written to the log More...
 
void write_load_output ()
 write the process load, which was previously initialized with initialize_load_output() More...
 
void debug_print_buffer (uint32_t &total_bytes, hrt_abstime &timer_start)
 Regularly print the buffer fill state (only if DBGPRINT is set) More...
 

Static Private Member Functions

static void perf_iterate_callback (perf_counter_t handle, void *user)
 callback to write the performance counters More...
 
static void print_load_callback (void *user)
 callback for print_load_buffer() to print the process load More...
 

Private Attributes

uint8_t * _msg_buffer {nullptr}
 
int _msg_buffer_len {0}
 
LogFileName _file_name [(int) LogType::Count]
 
bool _prev_state {false}
 previous state depending on logging mode (arming or aux1 state) More...
 
bool _manually_logging_override {false}
 
Statistics _statistics [(int) LogType::Count]
 
hrt_abstime _last_sync_time {0}
 last time a sync msg was sent More...
 
LogMode _log_mode
 
const bool _log_name_timestamp
 
Array< LoggerSubscription, MAX_TOPICS_NUM_subscriptions
 all subscriptions for full & mission log (in front) More...
 
MissionSubscription _mission_subscriptions [MAX_MISSION_TOPICS_NUM] {}
 additional data for mission subscriptions More...
 
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 More...
 
orb_advert_t _mavlink_log_pub {nullptr}
 
uint8_t _next_topic_id {0}
 id of next subscribed ulog topic More...
 
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 (for the full log) More...
 
print_load_s _load {}
 process load data More...
 
hrt_abstime _next_load_print {0}
 timestamp when to print the process load More...
 
PrintLoadReason _print_load_reason {PrintLoadReason::Preflight}
 
uORB::Subscription _manual_control_sp_sub {ORB_ID(manual_control_setpoint)}
 
uORB::Subscription _vehicle_command_sub {ORB_ID(vehicle_command)}
 
uORB::Subscription _vehicle_status_sub {ORB_ID(vehicle_status)}
 
uORB::SubscriptionInterval _log_message_sub {ORB_ID(log_message), 20}
 
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}
 

Static Private Attributes

static constexpr size_t MAX_TOPICS_NUM = 90
 Maximum number of logged topics. More...
 
static constexpr int MAX_MISSION_TOPICS_NUM = 5
 Maximum number of mission topics. More...
 
static constexpr unsigned MAX_NO_LOGFILE = 999
 Maximum number of log files. More...
 
static constexpr const char * LOG_ROOT [(int) LogType::Count]
 

Detailed Description

Definition at line 99 of file logger.h.

Member Typedef Documentation

◆ WrittenFormats

Array to store written formats (add some more for nested definitions)

Definition at line 253 of file logger.h.

Member Enumeration Documentation

◆ LogMode

Enumerator
while_armed 
boot_until_disarm 
boot_until_shutdown 
rc_aux1 

Definition at line 102 of file logger.h.

◆ PrintLoadReason

Enumerator
Preflight 
Postflight 
Watchdog 

Definition at line 169 of file logger.h.

Constructor & Destructor Documentation

◆ Logger()

px4::logger::Logger::Logger ( LogWriter::Backend  backend,
size_t  buffer_size,
uint32_t  log_interval,
const char *  poll_topic_name,
LogMode  log_mode,
bool  log_name_timestamp 
)

Definition at line 363 of file logger.cpp.

References _log_dirs_max, _log_utc_offset, _mission_log, _polling_topic_meta, _sdlog_profile_handle, orb_get_topics(), orb_topics_count(), and param_find().

Here is the call graph for this function:

◆ ~Logger()

px4::logger::Logger::~Logger ( )

Definition at line 391 of file logger.cpp.

References _msg_buffer, and _replay_file_name.

Member Function Documentation

◆ ack_vehicle_command()

void px4::logger::Logger::ack_vehicle_command ( vehicle_command_s cmd,
uint32_t  result 
)
private

Definition at line 2203 of file logger.cpp.

References vehicle_command_ack_s::command, vehicle_command_s::command, hrt_absolute_time(), ORB_ID, vehicle_command_ack_s::result, vehicle_command_s::source_component, vehicle_command_s::source_system, vehicle_command_ack_s::target_component, vehicle_command_ack_s::target_system, and vehicle_command_ack_s::timestamp.

Referenced by handle_vehicle_command_update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ add_debug_topics()

void px4::logger::Logger::add_debug_topics ( )
private

Definition at line 594 of file logger.cpp.

References add_topic().

Referenced by initialize_configured_topics().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ add_default_topics()

void px4::logger::Logger::add_default_topics ( )
private

Definition at line 509 of file logger.cpp.

References add_topic(), and add_topic_multi().

Referenced by initialize_configured_topics().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ add_estimator_replay_topics()

void px4::logger::Logger::add_estimator_replay_topics ( )
private

Definition at line 602 of file logger.cpp.

References add_topic(), and add_topic_multi().

Referenced by initialize_configured_topics().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ add_high_rate_topics()

void px4::logger::Logger::add_high_rate_topics ( )
private

Definition at line 580 of file logger.cpp.

References add_topic().

Referenced by initialize_configured_topics().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ add_mission_topic()

void px4::logger::Logger::add_mission_topic ( const char *  name,
uint32_t  interval_ms = 0 
)
private

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.

Parameters
nametopic name
intervallimit rate if >0 [ms], otherwise log as fast as the topic is updated.

Definition at line 786 of file logger.cpp.

References _mission_subscriptions, _num_mission_subs, add_topic(), MAX_MISSION_TOPICS_NUM, px4::logger::Logger::MissionSubscription::min_delta_ms, and px4::logger::Logger::MissionSubscription::next_write_time.

Referenced by initialize_mission_topics().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ add_sensor_comparison_topics()

void px4::logger::Logger::add_sensor_comparison_topics ( )
private

Definition at line 630 of file logger.cpp.

References add_topic_multi().

Referenced by initialize_configured_topics().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ add_system_identification_topics()

void px4::logger::Logger::add_system_identification_topics ( )
private

Definition at line 650 of file logger.cpp.

References add_topic().

Referenced by initialize_configured_topics().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ add_thermal_calibration_topics()

void px4::logger::Logger::add_thermal_calibration_topics ( )
private

Definition at line 623 of file logger.cpp.

References add_topic_multi().

Referenced by initialize_configured_topics().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ add_topic() [1/2]

bool px4::logger::Logger::add_topic ( const char *  name,
uint32_t  interval_ms = 0,
uint8_t  instance = 0 
)

Add a topic to be logged.

This must be called before start_log() (because it does not write an ADD_LOGGED_MSG message).

Parameters
nametopic name
intervallimit in milliseconds if >0, otherwise log as fast as the topic is updated.
instanceorb topic instance
Returns
true on success

Definition at line 434 of file logger.cpp.

References _polling_topic_meta, _subscriptions, ll40ls::instance, orb_get_topics(), and orb_topics_count().

Referenced by add_debug_topics(), add_default_topics(), add_estimator_replay_topics(), add_high_rate_topics(), add_mission_topic(), add_system_identification_topics(), add_topic_multi(), add_topics_from_file(), and add_vision_and_avoidance_topics().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ add_topic() [2/2]

LoggerSubscription * px4::logger::Logger::add_topic ( const orb_metadata topic,
uint32_t  interval_ms = 0,
uint8_t  instance = 0 
)

add a logged topic (called by add_topic() above).

In addition, it subscribes to the first instance of the topic, if it's advertised,

Returns
the newly added subscription on success, nullptr otherwise

Definition at line 412 of file logger.cpp.

References _subscriptions, ulog_message_format_s::format, orb_metadata::o_fields, and orb_metadata::o_name.

◆ add_topic_multi()

bool px4::logger::Logger::add_topic_multi ( const char *  name,
uint32_t  interval_ms = 0 
)

Definition at line 474 of file logger.cpp.

References add_topic(), ll40ls::instance, and ORB_MULTI_MAX_INSTANCES.

Referenced by add_default_topics(), add_estimator_replay_topics(), add_sensor_comparison_topics(), and add_thermal_calibration_topics().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ add_topics_from_file()

int px4::logger::Logger::add_topics_from_file ( const char *  fname)
private

Parse a file containing a list of uORB topics to log, calling add_topic for each.

Parameters
fnamename of file
Returns
number of topics added

Definition at line 658 of file logger.cpp.

References add_topic().

Referenced by run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ add_vision_and_avoidance_topics()

void px4::logger::Logger::add_vision_and_avoidance_topics ( )
private

Definition at line 638 of file logger.cpp.

References add_topic().

Referenced by initialize_configured_topics().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ can_start_mavlink_log()

bool px4::logger::Logger::can_start_mavlink_log ( ) const
inlineprivate

check if mavlink logging can be started

Definition at line 238 of file logger.h.

References px4::logger::LogWriter::BackendMavlink, and px4::logger::Full.

Referenced by handle_vehicle_command_update(), and start_log_mavlink().

Here is the caller graph for this function:

◆ configured_backend_mode()

const char * px4::logger::Logger::configured_backend_mode ( ) const
private

get the configured backend as string

Definition at line 710 of file logger.cpp.

References _writer, px4::logger::LogWriter::backend(), px4::logger::LogWriter::BackendAll, px4::logger::LogWriter::BackendFile, and px4::logger::LogWriter::BackendMavlink.

Referenced by run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ copy_if_updated()

bool px4::logger::Logger::copy_if_updated ( int  sub_idx,
void *  buffer,
bool  try_to_subscribe 
)
inlineprivate

Definition at line 484 of file logger.cpp.

References _num_mission_subs, _subscriptions, uORB::SubscriptionInterval::copy(), px4::logger::Full, px4::logger::Mission, uORB::SubscriptionInterval::subscribe(), uORB::SubscriptionInterval::update(), uORB::SubscriptionInterval::valid(), and write_add_logged_msg().

Referenced by run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ create_log_dir()

int px4::logger::Logger::create_log_dir ( LogType  type,
tm *  tt,
char *  log_dir,
int  log_dir_len 
)
private

Create logging directory.

Parameters
type
ttif not null, use it for the directory name
log_dirreturned log directory path
log_dir_lenlog_dir buffer length
Returns
string length of log_dir (excluding terminating null-char), <0 on error

Definition at line 1330 of file logger.cpp.

References _file_name, px4::logger::Logger::LogFileName::has_log_dir, px4::logger::Logger::LogFileName::log_dir, LOG_ROOT, OK, and px4::logger::Logger::LogFileName::sess_dir_index.

Referenced by get_log_file_name().

Here is the caller graph for this function:

◆ custom_command()

int px4::logger::Logger::custom_command ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 137 of file logger.cpp.

References is_running(), and print_usage().

Here is the call graph for this function:

◆ debug_print_buffer()

void px4::logger::Logger::debug_print_buffer ( uint32_t &  total_bytes,
hrt_abstime timer_start 
)
inlineprivate

Regularly print the buffer fill state (only if DBGPRINT is set)

Parameters
total_bytestotal written bytes (to the full file), will be reset on each print
timer_starttime since last print

Definition at line 1181 of file logger.cpp.

References _statistics, px4::logger::Logger::Statistics::high_water, hrt_absolute_time(), and px4::logger::Logger::Statistics::max_dropout_duration.

Referenced by run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_log_file_name()

int px4::logger::Logger::get_log_file_name ( LogType  type,
char *  file_name,
size_t  file_name_size 
)
private

Get log file name with directory (create it if necessary)

Definition at line 1391 of file logger.cpp.

References _file_name, _log_name_timestamp, _log_utc_offset, _replay_file_name, create_log_dir(), px4::logger::util::file_exist(), px4::logger::util::get_log_time(), px4::logger::Logger::LogFileName::log_file_name, MAX_NO_LOGFILE, param_get(), and PARAM_INVALID.

Referenced by start_log_file().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_vehicle_command_update()

void px4::logger::Logger::handle_vehicle_command_update ( )
private

Definition at line 1276 of file logger.cpp.

References _vehicle_command_sub, ack_vehicle_command(), can_start_mavlink_log(), command, vehicle_command_s::command, vehicle_command_s::param1, start_log_mavlink(), stop_log_mavlink(), and uORB::Subscription::update().

Referenced by run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ initialize_configured_topics()

void px4::logger::Logger::initialize_configured_topics ( )
private

Add topic subscriptions based on the _sdlog_profile_handle parameter.

Definition at line 736 of file logger.cpp.

References _sdlog_profile_handle, add_debug_topics(), add_default_topics(), add_estimator_replay_topics(), add_high_rate_topics(), add_sensor_comparison_topics(), add_system_identification_topics(), add_thermal_calibration_topics(), add_vision_and_avoidance_topics(), px4::logger::DEBUG_TOPICS, px4::logger::DEFAULT, px4::logger::ESTIMATOR_REPLAY, px4::logger::HIGH_RATE, param_get(), PARAM_INVALID, px4::logger::SENSOR_COMPARISON, px4::logger::SYSTEM_IDENTIFICATION, px4::logger::THERMAL_CALIBRATION, and px4::logger::VISION_AND_AVOIDANCE.

Referenced by run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ initialize_load_output()

void px4::logger::Logger::initialize_load_output ( PrintLoadReason  reason)
private

initialize the output for the process load, so that ~1 second later it will be written to the log

Definition at line 1634 of file logger.cpp.

References _load, _next_load_print, _print_load_reason, px4::logger::perf_callback_data_t::buffer, px4::logger::perf_callback_data_t::counter, hrt_absolute_time(), hrt_abstime, init_print_load_s(), px4::logger::perf_callback_data_t::logger, print_load_buffer(), and print_load_callback().

Referenced by run(), start_log_file(), start_log_mavlink(), and start_stop_logging().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ initialize_mission_topics()

void px4::logger::Logger::initialize_mission_topics ( MissionLogType  type)
private

Add topic subscriptions based on the configured mission log type.

Definition at line 723 of file logger.cpp.

References add_mission_topic(), px4::logger::Complete, and px4::logger::Geotagging.

Referenced by run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ instantiate()

Logger * px4::logger::Logger::instantiate ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 233 of file logger.cpp.

References backend, px4::logger::LogWriter::BackendAll, px4::logger::LogWriter::BackendFile, px4::logger::LogWriter::BackendMavlink, boot_until_disarm, boot_until_shutdown, rc_aux1, setReplayFile(), and while_armed.

Here is the call graph for this function:

◆ perf_iterate_callback()

void px4::logger::Logger::perf_iterate_callback ( perf_counter_t  handle,
void *  user 
)
staticprivate

callback to write the performance counters

Definition at line 1570 of file logger.cpp.

References px4::logger::perf_callback_data_t::counter, px4::logger::Full, px4::logger::perf_callback_data_t::logger, perf_print_counter_buffer(), px4::logger::perf_callback_data_t::preflight, and write_info_multiple().

Referenced by write_perf_data().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ print_load_callback()

void px4::logger::Logger::print_load_callback ( void *  user)
staticprivate

callback for print_load_buffer() to print the process load

Definition at line 1602 of file logger.cpp.

References _print_load_reason, px4::logger::perf_callback_data_t::buffer, px4::logger::perf_callback_data_t::counter, px4::logger::Full, px4::logger::perf_callback_data_t::logger, Postflight, Preflight, Watchdog, and write_info_multiple().

Referenced by initialize_load_output(), and write_load_output().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ print_statistics()

void px4::logger::Logger::print_statistics ( LogType  type)

Definition at line 204 of file logger.cpp.

References px4::logger::LogWriter::BackendFile, f(), px4::logger::Logger::Statistics::high_water, hrt_absolute_time(), px4::logger::Logger::Statistics::max_dropout_duration, px4::logger::Logger::Statistics::start_time_file, and px4::logger::Logger::Statistics::write_dropouts.

Here is the call graph for this function:

◆ print_status()

int px4::logger::Logger::print_status ( )
override
See also
ModuleBase::print_status()

Definition at line 174 of file logger.cpp.

References px4::logger::LogWriter::BackendFile, px4::logger::LogWriter::BackendMavlink, px4::logger::Full, and px4::logger::Mission.

◆ print_usage()

int px4::logger::Logger::print_usage ( const char *  reason = nullptr)
static
See also
ModuleBase

Definition at line 2216 of file logger.cpp.

◆ request_stop_static()

bool px4::logger::Logger::request_stop_static ( )
static

request the logger thread to stop (this method does not block).

Returns
true if the logger is stopped, false if (still) running

Definition at line 402 of file logger.cpp.

References is_running().

Referenced by run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ run()

void px4::logger::Logger::run ( )
override
See also
ModuleBase::run()

Definition at line 800 of file logger.cpp.

References _file_name, _last_sync_time, _log_dirs_max, _log_interval, _log_message_sub, _log_mode, _mavlink_log_pub, _mission_log, _mission_subscriptions, _msg_buffer, _msg_buffer_len, _next_load_print, _num_mission_subs, _polling_topic_meta, _should_stop_file_log, _statistics, _subscriptions, _writer, add_topics_from_file(), px4::logger::LogWriter::backend(), px4::logger::LogWriter::BackendFile, boot_until_disarm, boot_until_shutdown, px4::logger::util::check_free_space(), configured_backend_mode(), uORB::Subscription::copy(), copy_if_updated(), px4::logger::Count, DATA, debug_print_buffer(), px4::logger::Full, px4::logger::LogWriter::get_buffer_fill_count_file(), handle_vehicle_command_update(), px4::logger::Logger::Statistics::high_water, hrt_absolute_time(), hrt_abstime, hrt_call_every(), hrt_cancel(), px4::logger::LogWriter::init(), initialize_configured_topics(), initialize_load_output(), initialize_mission_topics(), px4::logger::LogWriter::is_started(), px4::logger::LogWriter::lock(), LOG_ROOT, LOGGING, ulog_message_logging_s::message, px4::logger::Logger::MissionSubscription::min_delta_ms, px4::logger::Mission, px4::logger::Logger::MissionSubscription::next_write_time, px4::logger::LogWriter::notify(), orb_metadata::o_size, orb_copy(), ORB_ID, orb_subscribe(), orb_unadvertise(), orb_unsubscribe(), param_get(), PARAM_INVALID, px4_poll(), request_stop_static(), timer_callback_data_s::semaphore, log_message_s::severity, start_log_file(), start_stop_logging(), stop_log_file(), SYNC, log_message_s::text, px4::logger::LogWriter::thread_id_file(), px4::logger::LogWriter::thread_stop(), timer_callback(), log_message_s::timestamp, ulog_message_logging_s::timestamp, TRY_SUBSCRIBE_INTERVAL, ULOG_MSG_HEADER_LEN, px4::logger::LogWriter::unlock(), uORB::SubscriptionInterval::update(), uORB::Subscription::updated(), Watchdog, timer_callback_data_s::watchdog_data, px4::logger::watchdog_initialize(), timer_callback_data_s::watchdog_triggered, write_changed_parameters(), write_load_output(), and write_message().

Here is the call graph for this function:

◆ set_arm_override()

void px4::logger::Logger::set_arm_override ( bool  override)
inline

Definition at line 165 of file logger.h.

◆ setReplayFile()

void px4::logger::Logger::setReplayFile ( const char *  file_name)

Tell the logger that we're in replay mode.

This must be called before starting the logger.

Parameters
file_namefile name of the used log replay file. Will be copied.

Definition at line 1458 of file logger.cpp.

References _replay_file_name.

Referenced by instantiate().

Here is the caller graph for this function:

◆ start_log_file()

void px4::logger::Logger::start_log_file ( LogType  type)
private

◆ start_log_mavlink()

void px4::logger::Logger::start_log_mavlink ( )
private

Definition at line 1531 of file logger.cpp.

References _writer, px4::logger::LogWriter::BackendMavlink, can_start_mavlink_log(), px4::logger::Full, initialize_load_output(), px4::logger::LogWriter::notify(), Preflight, px4::logger::LogWriter::select_write_backend(), px4::logger::LogWriter::set_need_reliable_transfer(), px4::logger::LogWriter::start_log_mavlink(), px4::logger::LogWriter::unselect_write_backend(), write_all_add_logged_msg(), write_console_output(), write_formats(), write_header(), write_parameters(), write_perf_data(), and write_version().

Referenced by handle_vehicle_command_update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ start_stop_logging()

bool px4::logger::Logger::start_stop_logging ( MissionLogType  mission_log_type)
private

check current arming state or aux channel and start/stop logging if state changed and according to configured params.

Parameters
vehicle_status_sub
manual_control_sp_sub
mission_log_type
Returns
true if log started

Definition at line 1202 of file logger.cpp.

References _log_mode, _manual_control_sp_sub, _manually_logging_override, _prev_state, _should_stop_file_log, _vehicle_status_sub, armed, vehicle_status_s::arming_state, manual_control_setpoint_s::aux1, boot_until_shutdown, px4::logger::Disabled, px4::logger::Full, initialize_load_output(), px4::logger::Mission, Postflight, rc_aux1, start_log_file(), stop_log_file(), and uORB::Subscription::update().

Referenced by run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ stop_log_file()

void px4::logger::Logger::stop_log_file ( LogType  type)
private

Definition at line 1516 of file logger.cpp.

References _writer, px4::logger::LogWriter::BackendFile, px4::logger::Full, px4::logger::LogWriter::is_started(), px4::logger::LogWriter::set_need_reliable_transfer(), px4::logger::LogWriter::stop_log_file(), and write_perf_data().

Referenced by run(), and start_stop_logging().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ stop_log_mavlink()

void px4::logger::Logger::stop_log_mavlink ( )
private

Definition at line 1556 of file logger.cpp.

References _writer, and px4::logger::LogWriter::stop_log_mavlink().

Referenced by handle_vehicle_command_update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ task_spawn()

int px4::logger::Logger::task_spawn ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 157 of file logger.cpp.

◆ write_add_logged_msg()

void px4::logger::Logger::write_add_logged_msg ( LogType  type,
LoggerSubscription subscription 
)
private

Write an ADD_LOGGED_MSG to the log for a given subscription and instance.

_writer.lock() must be held when calling this.

Definition at line 1836 of file logger.cpp.

References _next_topic_id, _writer, uORB::SubscriptionInterval::get_instance(), uORB::SubscriptionInterval::get_topic(), ulog_message_add_logged_s::message_name, msg, ulog_message_add_logged_s::msg_id, px4::logger::LoggerSubscription::msg_id, px4::logger::MSG_ID_INVALID, ulog_message_add_logged_s::msg_size, ulog_message_add_logged_s::multi_id, px4::logger::LogWriter::need_reliable_transfer(), orb_metadata::o_name, px4::logger::LogWriter::set_need_reliable_transfer(), ULOG_MSG_HEADER_LEN, and write_message().

Referenced by copy_if_updated(), and write_all_add_logged_msg().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_all_add_logged_msg()

void px4::logger::Logger::write_all_add_logged_msg ( LogType  type)
private

Write an ADD_LOGGED_MSG to the log for a all current subscriptions and instances.

Definition at line 1815 of file logger.cpp.

References _num_mission_subs, _subscriptions, _writer, px4::logger::LogWriter::lock(), px4::logger::Mission, px4::logger::LogWriter::unlock(), uORB::SubscriptionInterval::valid(), and write_add_logged_msg().

Referenced by start_log_file(), and start_log_mavlink().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_changed_parameters()

void px4::logger::Logger::write_changed_parameters ( LogType  type)
private

Definition at line 2132 of file logger.cpp.

References _writer, ulog_message_parameter_header_s::key, ulog_message_parameter_header_s::key_len, px4::logger::LogWriter::lock(), msg, ulog_message_parameter_header_s::msg_size, ulog_message_parameter_header_s::msg_type, px4::logger::LogWriter::notify(), param_count(), param_for_index(), param_get(), PARAM_INVALID, param_name(), param_type(), PARAM_TYPE_FLOAT, PARAM_TYPE_INT32, param_used(), param_value_unsaved(), PARAMETER, ULOG_MSG_HEADER_LEN, px4::logger::LogWriter::unlock(), and write_message().

Referenced by run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_console_output()

void px4::logger::Logger::write_console_output ( )
private

write bootup console output

Definition at line 1668 of file logger.cpp.

References px4::logger::Full, math::min(), and write_info_multiple().

Referenced by start_log_file(), and start_log_mavlink().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_format()

void px4::logger::Logger::write_format ( LogType  type,
const orb_metadata meta,
WrittenFormats written_formats,
ulog_message_format_s msg,
int  level = 1 
)
private

Definition at line 1690 of file logger.cpp.

References ulog_message_format_s::format, msg, ulog_message_format_s::msg_size, orb_metadata::o_fields, orb_metadata::o_name, orb_get_topics(), orb_topics_count(), ULOG_MSG_HEADER_LEN, and write_message().

Referenced by write_formats().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_formats()

void px4::logger::Logger::write_formats ( LogType  type)
private

Definition at line 1792 of file logger.cpp.

References _num_mission_subs, _subscriptions, _writer, uORB::SubscriptionInterval::get_topic(), px4::logger::LogWriter::lock(), px4::logger::Mission, msg, px4::logger::LogWriter::unlock(), and write_format().

Referenced by start_log_file(), and start_log_mavlink().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_header()

void px4::logger::Logger::write_header ( LogType  type)
private

write the file header with file magic and timestamp.

Definition at line 1954 of file logger.cpp.

References _writer, FLAG_BITS, hrt_absolute_time(), px4::logger::LogWriter::lock(), ulog_file_header_s::magic, ulog_message_flag_bits_s::msg_size, ulog_file_header_s::timestamp, ULOG_MSG_HEADER_LEN, px4::logger::LogWriter::unlock(), and write_message().

Referenced by start_log_file(), and start_log_mavlink().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_info() [1/3]

void px4::logger::Logger::write_info ( LogType  type,
const char *  name,
const char *  value 
)
private

Definition at line 1866 of file logger.cpp.

References _writer, INFO, ulog_message_info_header_s::key, ulog_message_info_header_s::key_len, px4::logger::LogWriter::lock(), msg, ulog_message_info_header_s::msg_size, ulog_message_info_header_s::msg_type, ULOG_MSG_HEADER_LEN, px4::logger::LogWriter::unlock(), and write_message().

Referenced by write_version().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_info() [2/3]

void px4::logger::Logger::write_info ( LogType  type,
const char *  name,
int32_t  value 
)
private

Definition at line 1920 of file logger.cpp.

References name.

◆ write_info() [3/3]

void px4::logger::Logger::write_info ( LogType  type,
const char *  name,
uint32_t  value 
)
private

Definition at line 1925 of file logger.cpp.

References name.

◆ write_info_multiple()

void px4::logger::Logger::write_info_multiple ( LogType  type,
const char *  name,
const char *  value,
bool  is_continued 
)
private

Definition at line 1891 of file logger.cpp.

References _writer, INFO_MULTIPLE, ulog_message_info_multiple_header_s::is_continued, ulog_message_info_multiple_header_s::key, ulog_message_info_multiple_header_s::key_len, px4::logger::LogWriter::lock(), msg, ulog_message_info_multiple_header_s::msg_size, ulog_message_info_multiple_header_s::msg_type, ULOG_MSG_HEADER_LEN, px4::logger::LogWriter::unlock(), and write_message().

Referenced by perf_iterate_callback(), print_load_callback(), and write_console_output().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_info_template()

template<typename T >
void px4::logger::Logger::write_info_template ( LogType  type,
const char *  name,
value,
const char *  type_str 
)
private

generic common template method for write_info variants

Definition at line 1932 of file logger.cpp.

References _writer, INFO, ulog_message_info_header_s::key, ulog_message_info_header_s::key_len, px4::logger::LogWriter::lock(), msg, ulog_message_info_header_s::msg_size, ulog_message_info_header_s::msg_type, ULOG_MSG_HEADER_LEN, px4::logger::LogWriter::unlock(), and write_message().

Here is the call graph for this function:

◆ write_load_output()

void px4::logger::Logger::write_load_output ( )
private

write the process load, which was previously initialized with initialize_load_output()

Definition at line 1649 of file logger.cpp.

References _load, _print_load_reason, _writer, px4::logger::perf_callback_data_t::buffer, px4::logger::perf_callback_data_t::counter, hrt_absolute_time(), hrt_abstime, px4::logger::perf_callback_data_t::logger, print_load_buffer(), print_load_callback(), px4::logger::LogWriter::set_need_reliable_transfer(), and Watchdog.

Referenced by run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_message()

bool px4::logger::Logger::write_message ( LogType  type,
void *  ptr,
size_t  size 
)
private

Write exactly one ulog message to the logger and handle dropouts.

Must be called with _writer.lock() held.

Returns
true if data written, false otherwise (on overflow)

Definition at line 1302 of file logger.cpp.

References _statistics, _writer, px4::logger::Logger::Statistics::dropout_start, px4::logger::Logger::Statistics::high_water, hrt_absolute_time(), hrt_elapsed_time(), px4::logger::Logger::Statistics::max_dropout_duration, px4::logger::Logger::Statistics::write_dropouts, and px4::logger::LogWriter::write_message().

Referenced by run(), write_add_logged_msg(), write_changed_parameters(), write_format(), write_header(), write_info(), write_info_multiple(), write_info_template(), and write_parameters().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_parameters()

void px4::logger::Logger::write_parameters ( LogType  type)
private

Definition at line 2063 of file logger.cpp.

References _writer, ulog_message_parameter_header_s::key, ulog_message_parameter_header_s::key_len, px4::logger::LogWriter::lock(), msg, ulog_message_parameter_header_s::msg_size, ulog_message_parameter_header_s::msg_type, px4::logger::LogWriter::notify(), param_count(), param_for_index(), param_get(), PARAM_INVALID, param_name(), param_type(), PARAM_TYPE_FLOAT, PARAM_TYPE_INT32, param_used(), PARAMETER, ULOG_MSG_HEADER_LEN, px4::logger::LogWriter::unlock(), and write_message().

Referenced by start_log_file(), and start_log_mavlink().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_perf_data()

void px4::logger::Logger::write_perf_data ( bool  preflight)
private

write performance counters

Parameters
preflightpreflight if true, postflight otherwise

Definition at line 1590 of file logger.cpp.

References px4::logger::perf_callback_data_t::counter, px4::logger::perf_callback_data_t::logger, perf_iterate_all(), perf_iterate_callback(), and px4::logger::perf_callback_data_t::preflight.

Referenced by start_log_file(), start_log_mavlink(), and stop_log_file().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ write_version()

void px4::logger::Logger::write_version ( LogType  type)
private

Definition at line 1980 of file logger.cpp.

References _log_utc_offset, _replay_file_name, px4::logger::Mission, param_find(), param_get(), PARAM_INVALID, px4_board_name(), px4_board_sub_type(), px4_ecl_lib_version_string(), px4_firmware_git_branch(), px4_firmware_vendor_version(), px4_firmware_version(), px4_firmware_version_string(), px4_os_name(), px4_os_version(), px4_os_version_string(), px4_toolchain_name(), px4_toolchain_version(), and write_info().

Referenced by start_log_file(), and start_log_mavlink().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _file_name

LogFileName px4::logger::Logger::_file_name[(int) LogType::Count]
private

Definition at line 373 of file logger.h.

Referenced by create_log_dir(), get_log_file_name(), and run().

◆ _last_sync_time

hrt_abstime px4::logger::Logger::_last_sync_time {0}
private

last time a sync msg was sent

Definition at line 379 of file logger.h.

Referenced by run().

◆ _load

print_load_s px4::logger::Logger::_load {}
private

process load data

Definition at line 396 of file logger.h.

Referenced by initialize_load_output(), and write_load_output().

◆ _log_dirs_max

param_t px4::logger::Logger::_log_dirs_max {PARAM_INVALID}
private

Definition at line 407 of file logger.h.

Referenced by Logger(), and run().

◆ _log_interval

uint32_t px4::logger::Logger::_log_interval {0}
private

Definition at line 389 of file logger.h.

Referenced by run().

◆ _log_message_sub

uORB::SubscriptionInterval px4::logger::Logger::_log_message_sub {ORB_ID(log_message), 20}
private

Definition at line 403 of file logger.h.

Referenced by run().

◆ _log_mode

LogMode px4::logger::Logger::_log_mode
private

Definition at line 381 of file logger.h.

Referenced by run(), and start_stop_logging().

◆ _log_name_timestamp

const bool px4::logger::Logger::_log_name_timestamp
private

Definition at line 382 of file logger.h.

Referenced by get_log_file_name().

◆ _log_utc_offset

param_t px4::logger::Logger::_log_utc_offset {PARAM_INVALID}
private

Definition at line 406 of file logger.h.

Referenced by get_log_file_name(), Logger(), and write_version().

◆ _manual_control_sp_sub

uORB::Subscription px4::logger::Logger::_manual_control_sp_sub {ORB_ID(manual_control_setpoint)}
private

Definition at line 400 of file logger.h.

Referenced by start_stop_logging().

◆ _manually_logging_override

bool px4::logger::Logger::_manually_logging_override {false}
private

Definition at line 376 of file logger.h.

Referenced by start_stop_logging().

◆ _mavlink_log_pub

orb_advert_t px4::logger::Logger::_mavlink_log_pub {nullptr}
private

Definition at line 391 of file logger.h.

Referenced by run(), and start_log_file().

◆ _mission_log

param_t px4::logger::Logger::_mission_log {PARAM_INVALID}
private

Definition at line 408 of file logger.h.

Referenced by Logger(), and run().

◆ _mission_subscriptions

MissionSubscription px4::logger::Logger::_mission_subscriptions[MAX_MISSION_TOPICS_NUM] {}
private

additional data for mission subscriptions

Definition at line 385 of file logger.h.

Referenced by add_mission_topic(), and run().

◆ _msg_buffer

uint8_t* px4::logger::Logger::_msg_buffer {nullptr}
private

Definition at line 370 of file logger.h.

Referenced by run(), and ~Logger().

◆ _msg_buffer_len

int px4::logger::Logger::_msg_buffer_len {0}
private

Definition at line 371 of file logger.h.

Referenced by run().

◆ _next_load_print

hrt_abstime px4::logger::Logger::_next_load_print {0}
private

timestamp when to print the process load

Definition at line 397 of file logger.h.

Referenced by initialize_load_output(), and run().

◆ _next_topic_id

uint8_t px4::logger::Logger::_next_topic_id {0}
private

id of next subscribed ulog topic

Definition at line 392 of file logger.h.

Referenced by write_add_logged_msg().

◆ _num_mission_subs

int px4::logger::Logger::_num_mission_subs {0}
private

◆ _polling_topic_meta

const orb_metadata* px4::logger::Logger::_polling_topic_meta {nullptr}
private

if non-null, poll on this topic instead of sleeping

Definition at line 390 of file logger.h.

Referenced by add_topic(), Logger(), and run().

◆ _prev_state

bool px4::logger::Logger::_prev_state {false}
private

previous state depending on logging mode (arming or aux1 state)

Definition at line 375 of file logger.h.

Referenced by start_stop_logging().

◆ _print_load_reason

PrintLoadReason px4::logger::Logger::_print_load_reason {PrintLoadReason::Preflight}
private

Definition at line 398 of file logger.h.

Referenced by initialize_load_output(), print_load_callback(), and write_load_output().

◆ _replay_file_name

char* px4::logger::Logger::_replay_file_name {nullptr}
private

Definition at line 393 of file logger.h.

Referenced by get_log_file_name(), setReplayFile(), write_version(), and ~Logger().

◆ _sdlog_profile_handle

param_t px4::logger::Logger::_sdlog_profile_handle {PARAM_INVALID}
private

Definition at line 405 of file logger.h.

Referenced by initialize_configured_topics(), and Logger().

◆ _should_stop_file_log

bool px4::logger::Logger::_should_stop_file_log {false}
private

if true _next_load_print is set and file logging will be stopped after load printing (for the full log)

Definition at line 394 of file logger.h.

Referenced by run(), and start_stop_logging().

◆ _statistics

Statistics px4::logger::Logger::_statistics[(int) LogType::Count]
private

Definition at line 378 of file logger.h.

Referenced by debug_print_buffer(), run(), start_log_file(), and write_message().

◆ _subscriptions

Array<LoggerSubscription, MAX_TOPICS_NUM> px4::logger::Logger::_subscriptions
private

all subscriptions for full & mission log (in front)

Definition at line 384 of file logger.h.

Referenced by add_topic(), copy_if_updated(), run(), write_all_add_logged_msg(), and write_formats().

◆ _vehicle_command_sub

uORB::Subscription px4::logger::Logger::_vehicle_command_sub {ORB_ID(vehicle_command)}
private

Definition at line 401 of file logger.h.

Referenced by handle_vehicle_command_update().

◆ _vehicle_status_sub

uORB::Subscription px4::logger::Logger::_vehicle_status_sub {ORB_ID(vehicle_status)}
private

Definition at line 402 of file logger.h.

Referenced by start_stop_logging().

◆ _writer

◆ LOG_ROOT

constexpr const char * px4::logger::Logger::LOG_ROOT
staticprivate
Initial value:
= {
PX4_STORAGEDIR "/log",
PX4_STORAGEDIR "/mission_log"
}

Definition at line 178 of file logger.h.

Referenced by create_log_dir(), logger_main(), and run().

◆ MAX_MISSION_TOPICS_NUM

constexpr int px4::logger::Logger::MAX_MISSION_TOPICS_NUM = 5
staticprivate

Maximum number of mission topics.

Definition at line 176 of file logger.h.

Referenced by add_mission_topic().

◆ MAX_NO_LOGFILE

constexpr unsigned px4::logger::Logger::MAX_NO_LOGFILE = 999
staticprivate

Maximum number of log files.

Definition at line 177 of file logger.h.

Referenced by get_log_file_name().

◆ MAX_TOPICS_NUM

constexpr size_t px4::logger::Logger::MAX_TOPICS_NUM = 90
staticprivate

Maximum number of logged topics.

Definition at line 175 of file logger.h.


The documentation for this class was generated from the following files: