PX4 Firmware
PX4 Autopilot Software http://px4.io
mavlink_log.h File Reference
#include <px4_log.h>
#include <uORB/uORB.h>
Include dependency graph for mavlink_log.h:

Go to the source code of this file.

Classes

struct  mavlink_logmessage
 
struct  mavlink_logbuffer
 

Macros

#define MAVLINK_LOG_MAXLEN   50
 The maximum string length supported. More...
 
#define _MSG_PRIO_DEBUG   7
 
#define _MSG_PRIO_INFO   6
 
#define _MSG_PRIO_NOTICE   5
 
#define _MSG_PRIO_WARNING   4
 
#define _MSG_PRIO_ERROR   3
 
#define _MSG_PRIO_CRITICAL   2
 
#define _MSG_PRIO_ALERT   1
 
#define _MSG_PRIO_EMERGENCY   0
 
#define mavlink_log_info(_pub, _text, ...)   mavlink_vasprintf(_MSG_PRIO_INFO, _pub, _text, ##__VA_ARGS__);
 Send a mavlink info message (not printed to console). More...
 
#define mavlink_log_warning(_pub, _text, ...)
 Send a mavlink warning message and print to console. More...
 
#define mavlink_log_emergency(_pub, _text, ...)
 Send a mavlink emergency message and print to console. More...
 
#define mavlink_log_critical(_pub, _text, ...)
 Send a mavlink critical message and print to console. More...
 
#define mavlink_and_console_log_info(_pub, _text, ...)
 Send a mavlink emergency message and print to console. More...
 

Functions

__EXPORT void mavlink_vasprintf (int severity, orb_advert_t *mavlink_log_pub, const char *fmt,...)
 

Macro Definition Documentation

◆ _MSG_PRIO_ALERT

#define _MSG_PRIO_ALERT   1

Definition at line 66 of file mavlink_log.h.

◆ _MSG_PRIO_CRITICAL

#define _MSG_PRIO_CRITICAL   2

Definition at line 65 of file mavlink_log.h.

◆ _MSG_PRIO_DEBUG

#define _MSG_PRIO_DEBUG   7

Definition at line 60 of file mavlink_log.h.

◆ _MSG_PRIO_EMERGENCY

#define _MSG_PRIO_EMERGENCY   0

Definition at line 67 of file mavlink_log.h.

◆ _MSG_PRIO_ERROR

#define _MSG_PRIO_ERROR   3

Definition at line 64 of file mavlink_log.h.

◆ _MSG_PRIO_INFO

#define _MSG_PRIO_INFO   6

Definition at line 61 of file mavlink_log.h.

◆ _MSG_PRIO_NOTICE

#define _MSG_PRIO_NOTICE   5

Definition at line 62 of file mavlink_log.h.

◆ _MSG_PRIO_WARNING

#define _MSG_PRIO_WARNING   4

Definition at line 63 of file mavlink_log.h.

◆ mavlink_and_console_log_info

#define mavlink_and_console_log_info (   _pub,
  _text,
  ... 
)
Value:
do { \
mavlink_log_info(_pub, _text, ##__VA_ARGS__); \
PX4_INFO(_text, ##__VA_ARGS__); \
} while(0);

Send a mavlink emergency message and print to console.

Parameters
_pubPointer to the uORB advert;
_textThe text to log;

Definition at line 126 of file mavlink_log.h.

Referenced by BlockLocalPositionEstimator::baroCheckTimeout(), BlockLocalPositionEstimator::baroCorrect(), BlockLocalPositionEstimator::baroInit(), Mission::do_abort_landing(), BlockLocalPositionEstimator::flowCorrect(), BlockLocalPositionEstimator::flowInit(), BlockLocalPositionEstimator::getDelayPeriods(), BlockLocalPositionEstimator::gpsCorrect(), BlockLocalPositionEstimator::gpsInit(), Commander::handle_command(), BlockLocalPositionEstimator::landCheckTimeout(), BlockLocalPositionEstimator::landCorrect(), BlockLocalPositionEstimator::landingTargetCheckTimeout(), BlockLocalPositionEstimator::landingTargetCorrect(), BlockLocalPositionEstimator::landingTargetInit(), BlockLocalPositionEstimator::landInit(), BlockLocalPositionEstimator::lidarCheckTimeout(), BlockLocalPositionEstimator::lidarCorrect(), BlockLocalPositionEstimator::lidarInit(), PX4IO::mixer_send(), BlockLocalPositionEstimator::mocapCheckTimeout(), BlockLocalPositionEstimator::mocapCorrect(), BlockLocalPositionEstimator::mocapInit(), RTL::on_activation(), Commander::run(), Navigator::run(), BlockLocalPositionEstimator::Run(), RTL::set_rtl_item(), BlockLocalPositionEstimator::sonarCheckTimeout(), BlockLocalPositionEstimator::sonarCorrect(), BlockLocalPositionEstimator::sonarInit(), Mavlink::task_main(), AirspeedModule::task_spawn(), AirspeedModule::update_params(), BlockLocalPositionEstimator::visionCorrect(), and BlockLocalPositionEstimator::visionInit().

◆ mavlink_log_critical

#define mavlink_log_critical (   _pub,
  _text,
  ... 
)
Value:
do { \
mavlink_vasprintf(_MSG_PRIO_CRITICAL, _pub, _text, ##__VA_ARGS__); \
PX4_WARN(_text, ##__VA_ARGS__); \
} while(0);

Send a mavlink critical message and print to console.

Parameters
_pubPointer to the uORB advert;
_textThe text to log;

Definition at line 114 of file mavlink_log.h.

Referenced by CollisionPrevention::_addObstacleSensorData(), _auth_method_arm_req_check(), _auth_method_two_arm_check(), CollisionPrevention::_calculateConstrainedSetpoint(), DfMPU6050Wrapper::_publish(), DfLsm9ds1Wrapper::_publish(), DfMpu9250Wrapper::_publish(), VtolAttitudeControl::abort_front_transition(), FixedwingPositionControl::abort_landing(), PreFlightCheck::accelerometerCheck(), DataLinkLoss::advance_dll(), GpsFailure::advance_gpsf(), RCLoss::advance_rcl(), PreFlightCheck::airspeedCheck(), arm_auth_update(), arming_state_transition(), PreFlightCheck::baroCheck(), BlockLocalPositionEstimator::baroCorrect(), battery_failsafe(), Commander::battery_status_check(), calibrate_answer_command(), calibrate_cancel_check(), px4::logger::util::check_free_space(), Navigator::check_traffic(), Geofence::checkAll(), MissionFeasibilityChecker::checkDistancesBetweenWaypoints(), MissionFeasibilityChecker::checkDistanceToFirstWaypoint(), MissionFeasibilityChecker::checkFixedWingLanding(), MissionFeasibilityChecker::checkGeofence(), MissionFeasibilityChecker::checkHomePositionAltitude(), MissionFeasibilityChecker::checkMissionItemValidity(), MissionFeasibilityChecker::checkTakeoff(), commander_low_prio_loop(), FixedwingPositionControl::control_takeoff(), Commander::data_link_check(), do_trim_calibration(), PX4IO::dsm_bind_ioctl(), PreFlightCheck::ekf2Check(), enable_failsafe(), Commander::esc_status_check(), Commander::estimator_check(), PreFlightCheck::failureDetectorCheck(), RTL::find_RTL_destination(), BlockLocalPositionEstimator::flowCheckTimeout(), BlockLocalPositionEstimator::gpsCheckTimeout(), BlockLocalPositionEstimator::gpsCorrect(), PreFlightCheck::gyroCheck(), Commander::handle_command(), PreFlightCheck::imuConsistencyCheck(), FixedwingPositionControl::init(), PX4IO::init(), PX4IO::io_set_rc_config(), Geofence::loadFromFile(), PreFlightCheck::magConsistencyCheck(), PreFlightCheck::magnometerCheck(), MulticopterPositionControl::parameters_update(), PreFlightCheck::powerCheck(), PreFlightCheck::preArmCheck(), PreFlightCheck::preflightCheck(), print_reject_arm(), print_reject_mode(), PreFlightCheck::rcCalibrationCheck(), Mission::read_mission_item(), Mission::reset_mission(), Commander::run(), Navigator::run(), Mission::save_mission_state(), AirspeedModule::select_airspeed_and_publish(), Mavlink::send_statustext_critical(), Navigator::set_mission_failure(), Mission::set_mission_items(), RTL::set_rtl_item(), Takeoff::set_takeoff_position(), PX4IO::task_main(), and BlockLocalPositionEstimator::visionCheckTimeout().

◆ mavlink_log_emergency

#define mavlink_log_emergency (   _pub,
  _text,
  ... 
)
Value:
do { \
mavlink_vasprintf(_MSG_PRIO_EMERGENCY, _pub, _text, ##__VA_ARGS__); \
PX4_ERR(_text, ##__VA_ARGS__); \
} while(0);

Send a mavlink emergency message and print to console.

Parameters
_pubPointer to the uORB advert;
_textThe text to log;

Definition at line 102 of file mavlink_log.h.

Referenced by EngineFailure::advance_ef(), GpsFailure::advance_gpsf(), battery_failsafe(), sensors::VotedSensorsUpdate::checkFailover(), PX4IO::detect(), Commander::estimator_check(), PX4IO::init(), Commander::run(), and Mavlink::send_statustext_emergency().

◆ mavlink_log_info

◆ MAVLINK_LOG_MAXLEN

#define MAVLINK_LOG_MAXLEN   50

The maximum string length supported.

Definition at line 50 of file mavlink_log.h.

◆ mavlink_log_warning

#define mavlink_log_warning (   _pub,
  _text,
  ... 
)
Value:
do { \
mavlink_vasprintf(_MSG_PRIO_WARNING, _pub, _text, ##__VA_ARGS__); \
PX4_WARN(_text, ##__VA_ARGS__); \
} while(0);

Send a mavlink warning message and print to console.

Parameters
_pubPointer to the uORB advert;
_textThe text to log;

Definition at line 90 of file mavlink_log.h.

Referenced by PreFlightCheck::ekf2Check(), and Commander::handle_command().

Function Documentation

◆ mavlink_vasprintf()

__EXPORT void mavlink_vasprintf ( int  severity,
orb_advert_t mavlink_log_pub,
const char *  fmt,
  ... 
)

Definition at line 51 of file mavlink_log.cpp.

References hrt_absolute_time(), orb_advertise_queue(), ORB_ID, orb_publish(), mavlink_log_s::severity, mavlink_log_s::text, and mavlink_log_s::timestamp.

Here is the call graph for this function: