Browse Source

px4_log.h: remove hrt_absolute_time() declaration (it does not belong here)

sbg
Beat Küng 9 years ago
parent
commit
e2afb0be6b
  1. 1
      src/drivers/device/integrator.cpp
  2. 1
      src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp
  3. 1
      src/modules/systemlib/mavlink_log.c
  4. 1
      src/modules/uavcan/sensors/baro.cpp
  5. 1
      src/modules/uavcan/sensors/gnss.cpp
  6. 1
      src/modules/uavcan/sensors/mag.cpp
  7. 1
      src/platforms/px4_log.h

1
src/drivers/device/integrator.cpp

@ -41,6 +41,7 @@ @@ -41,6 +41,7 @@
*/
#include "integrator.h"
#include <drivers/drv_hrt.h>
Integrator::Integrator(uint64_t auto_reset_interval, bool coning_compensation) :
_auto_reset_interval(auto_reset_interval),

1
src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp

@ -1,4 +1,5 @@ @@ -1,4 +1,5 @@
#include "BlockLocalPositionEstimator.hpp"
#include <drivers/drv_hrt.h>
#include <systemlib/mavlink_log.h>
#include <fcntl.h>
#include <systemlib/err.h>

1
src/modules/systemlib/mavlink_log.c

@ -38,6 +38,7 @@ @@ -38,6 +38,7 @@
* @author Lorenz Meier <lorenz@px4.io>
*/
#include <drivers/drv_hrt.h>
#include <px4_posix.h>
#include <string.h>
#include <stdlib.h>

1
src/modules/uavcan/sensors/baro.cpp

@ -35,6 +35,7 @@ @@ -35,6 +35,7 @@
* @author Pavel Kirienko <pavel.kirienko@gmail.com>
*/
#include <drivers/drv_hrt.h>
#include "baro.hpp"
#include <cmath>

1
src/modules/uavcan/sensors/gnss.cpp

@ -40,6 +40,7 @@ @@ -40,6 +40,7 @@
*/
#include "gnss.hpp"
#include <drivers/drv_hrt.h>
#include <systemlib/err.h>
#include <mathlib/mathlib.h>

1
src/modules/uavcan/sensors/mag.cpp

@ -37,6 +37,7 @@ @@ -37,6 +37,7 @@
#include "mag.hpp"
#include <drivers/drv_hrt.h>
#include <systemlib/err.h>
const char *const UavcanMagnetometerBridge::NAME = "mag";

1
src/platforms/px4_log.h

@ -127,7 +127,6 @@ static inline void do_nothing(int level, ...) @@ -127,7 +127,6 @@ static inline void do_nothing(int level, ...)
#include <px4_defines.h>
__BEGIN_DECLS
__EXPORT extern uint64_t hrt_absolute_time(void);
__EXPORT extern const char *__px4_log_level_str[_PX4_LOG_LEVEL_PANIC + 1];
__EXPORT extern const char *__px4_log_level_color[_PX4_LOG_LEVEL_PANIC + 1];

Loading…
Cancel
Save