PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Simple error/warning functions, heavily inspired by the BSD functions of the same names. More...
#include <px4_platform_common/log.h>
#include <stdarg.h>
#include <errno.h>
#include <stdlib.h>
Go to the source code of this file.
Macros | |
#define | EXIT(eval) px4_task_exit(eval) |
#define | err(eval, ...) |
#define | errx(eval, ...) |
#define | warn(...) PX4_WARN(__VA_ARGS__) |
#define | warnx(...) PX4_WARN(__VA_ARGS__) |
Simple error/warning functions, heavily inspired by the BSD functions of the same names.
The err() and warn() family of functions display a formatted error message on the standard error output. In all cases, the last component of the program name, a colon character, and a space are output. If the fmt argument is not NULL, the printf(3)-like formatted error message is output. The output is terminated by a newline character.
The err(), errc(), verr(), verrc(), warn(), warnc(), vwarn(), and vwarnc() functions append an error message obtained from strerror(3) based on a supplied error code value or the global variable errno, preceded by another colon and space unless the fmt argument is NULL.
In the case of the errc(), verrc(), warnc(), and vwarnc() functions, the code argument is used to look up the error message.
The err(), verr(), warn(), and vwarn() functions use the global variable errno to look up the error message.
The errx() and warnx() functions do not append an error message.
The err(), verr(), errc(), verrc(), errx(), and verrx() functions do not return, but exit with the value of the argument eval.
Definition in file err.h.
#define err | ( | eval, | |
... | |||
) |
Definition at line 83 of file err.h.
Referenced by ist8310::calibrate(), MatrixTest::dcmRenormTests(), LinuxGPIO::exportPin(), MPU6000::factory_self_test(), main(), GPS::pollOrRead(), pwm_main(), LinuxGPIO::readValue(), mpl3115a2::reset(), lps25h::reset(), bma180::reset(), qmc5883::reset(), ist8310::reset(), RoboClaw::RoboClaw(), PX4IO::set_update_rate(), LinuxGPIO::setDirection(), mpl3115a2::test(), lps25h::test(), bma180::test(), qmc5883::test(), ist8310::test(), LinuxGPIO::unexportPin(), and LinuxGPIO::writeValue().
#define errx | ( | eval, | |
... | |||
) |
Definition at line 89 of file err.h.
Referenced by bma180_main(), bst_main(), mpu6000::factorytest(), lps22hb::find_bus(), rm3100::find_bus(), mpu6000::find_bus(), mpl3115a2::find_bus(), lps25h::find_bus(), qmc5883::find_bus(), ist8310::find_bus(), hott_sensors_main(), hott_sensors_thread_main(), hott_telemetry_main(), hott_telemetry_thread_main(), pmw3902::info(), bmi160::info(), lsm303d::info(), pmw3901::info(), lsm303agr::info(), bmi088::info(), bmi055::info(), mpu6000::info(), IRLOCK::info(), bma180::info(), l3gd20::info(), rm3100::init(), lis3mdl::init(), PX4IO::init(), irlock_main(), lps25h_main(), lsm303agr_main(), lsm303d_main(), mkblctrl_main(), pca9685_main(), pwmin_reset(), pwmin_start(), pwmin_test(), px4io_main(), qmc5883_main(), bmi160::regdump(), bmi088::regdump(), bmi055::regdump(), mpu6000::regdump(), l3gd20::regdump(), mpu6000::reset(), PX4IO::set_update_rate(), pmw3902::start(), fxas21002c::start(), bmi160::start(), pmw3901::start(), lsm303d::start(), lsm303agr::start(), bmi088::start(), bmi055::start(), test_ppm::start(), bma180::start(), l3gd20::start(), rm3100::start_bus(), lis3mdl::start_bus(), mpl3115a2::start_bus(), lps25h::start_bus(), qmc5883::start_bus(), ist8310::start_bus(), pmw3902::stop(), pmw3901::stop(), IRLOCK::test(), mpl3115a2::test(), lps25h::test(), bma180::test(), qmc5883::test(), ist8310::test(), l3gd20::test_error(), test_ppm_main(), bmi160::testerror(), bmi055::testerror(), bmi088::testerror(), mpu6000::testerror(), uavcan_main(), uavcanesc_main(), and uavcannode_main().
#define warn | ( | ... | ) | PX4_WARN(__VA_ARGS__) |
Definition at line 94 of file err.h.
Referenced by blinkm_main(), HMC5883::calibrate(), LIS3MDL::calibrate(), commander_low_prio_loop(), Sensors::parameter_update_poll(), Commander::run(), RoverPositionControl::run(), PX4IO::set_update_rate(), CameraFeedback::start(), rc_receiver::start(), uart_esc::start(), mpu9x50::start(), RoverPositionControl::task_spawn(), and test_file().
#define warnx | ( | ... | ) | PX4_WARN(__VA_ARGS__) |
Definition at line 95 of file err.h.
Referenced by DataLinkLoss::advance_dll(), RCLoss::advance_rcl(), blinkm_main(), blinkm_usage(), bst_main(), HMC5883::calibrate(), check_user_abort(), decode_callback(), RoboClaw::getMotorPosition(), RoboClaw::getMotorSpeed(), Commander::handle_command(), RestartRequestHandler::handleRestartRequest(), hott_sensors_main(), hott_sensors_thread_main(), hott_telemetry_main(), hott_telemetry_thread_main(), IRLOCK::info(), PCA9685::info(), ets_airspeed::info(), mpl3115a2::info(), lps25h::info(), qmc5883::info(), MPL3115A2::init(), MS5611::init(), BlinkM::init(), BMA180::init(), MK::init(), PCA9685::ioctl(), irlock_main(), irlock_usage(), mag_calibration_worker(), PX4IO::mixer_send(), nshterm_main(), pca9685_main(), pca9685_usage(), PX4IO::print_debug(), print_usage(), px4::bst::BST::probe(), px4io_main(), recv_req_id(), PCA9685::reset(), Commander::run(), RoverPositionControl::run(), UavcanNode::run(), test_ppm::set(), DataLinkLoss::set_dll_item(), Commander::set_main_state_rc(), RCLoss::set_rcl_item(), PX4IO::set_update_rate(), rm3100::start_bus(), mpu6000::start_bus(), lis3mdl::start_bus(), mpl3115a2::start_bus(), lps25h::start_bus(), qmc5883::start_bus(), bmi160::stop(), bmi055::stop(), bmi088::stop(), mpu6000::stop(), test_ppm::stop(), PX4IO::task_main(), IRLOCK::test(), qmc5883::test(), test_file(), test_param(), test_ppm_loopback(), test_servo(), uavcannode_start(), usage(), bmi160::usage(), bmi055::usage(), bmi088::usage(), mpu6000::usage(), test_ppm::usage(), hmc5883::usage(), mpl3115a2::usage(), lps25h::usage(), l3gd20::usage(), qmc5883::usage(), and write_otp().