Remaining fixes needed before running Tools/fix_headers.sh

<systemlib/err.h> --> "systemlib/err.h" that fix_headers.sh
would miss because it comes after code it doesn't understand.

Effectively remove the '__EXPORT extern perf_counter_t perf_alloc('
line, because currently perf_alloc is defined to be NULL, and
after running fix_headers.sh that happens *before* this header
is included (the order of headers will be changed).

Do not define NULL to be (void*)0: that only works for C.
In fact, the conversions needed for NULL are so full of exceptions
that standard C++ introduced a new *keyword*: nullptr.
That's what we really should be using for C++ code.
In this case I just include the correct header to define NULL
the correct way.

Not really related to the header line:
Removed an #include <time.h> because I noted that px4_time.h
was already included... and moved a #include <sys/time.h>
to the top of the file (not really a fan of including headers
in the middle unless absolutely necessary).
Removed a include of queue.h because I noted it wasn't used.
This commit is contained in:
Carlo Wood 2016-10-24 18:42:48 +02:00 committed by Lorenz Meier
parent ebeb187522
commit de85fbe1dc
7 changed files with 17 additions and 11 deletions

View File

@ -294,7 +294,7 @@ perf_end(perf_counter_t handle)
}
}
#include <systemlib/err.h>
#include "systemlib/err.h"
void
perf_set_elapsed(perf_counter_t handle, int64_t elapsed)

View File

@ -64,7 +64,9 @@ __BEGIN_DECLS
* @return Handle for the new counter, or NULL if a counter
* could not be allocated.
*/
#ifndef perf_alloc // perf_alloc might be defined to be NULL in src/modules/px4iofirmware/px4io.h
__EXPORT extern perf_counter_t perf_alloc(enum perf_counter_type type, const char *name);
#endif
/**
* Get the reference to an existing counter or create a new one if it does not exist.

View File

@ -42,6 +42,12 @@
#include <sys/types.h>
#ifdef __cplusplus
#include <cstddef> // NULL
#else
#include <stddef.h> // NULL
#endif
/************************************************************************
* Pre-processor Definitions
************************************************************************/
@ -61,9 +67,6 @@
// Required for Linux
#define FAR
#ifndef NULL
#define NULL (void *)0
#endif
/************************************************************************
* Global Type Declarations

View File

@ -94,7 +94,6 @@ static void hrt_unlock(void)
}
#if defined(__PX4_APPLE_LEGACY)
#include <time.h>
#include <sys/time.h>
int px4_clock_gettime(clockid_t clk_id, struct timespec *tp)

View File

@ -39,8 +39,8 @@
#include <px4_config.h>
#include <px4_defines.h>
#include <queue.h>
#include <px4_workqueue.h>
#include "hrt_work.h"
/****************************************************************************

View File

@ -42,6 +42,12 @@
#include <sys/types.h>
#ifdef __cplusplus
#include <cstddef> // NULL
#else
#include <stddef.h> // NULL
#endif
/************************************************************************
* Pre-processor Definitions
************************************************************************/
@ -61,9 +67,6 @@
// Required for Linux
#define FAR
#ifndef NULL
#define NULL (void *)0
#endif
/************************************************************************
* Global Type Declarations

View File

@ -42,6 +42,7 @@
#include <drivers/drv_hrt.h>
#include <semaphore.h>
#include <time.h>
#include <sys/time.h>
#include <dspal_time.h>
#include <string.h>
#include <stdio.h>
@ -63,8 +64,6 @@ static void hrt_call_reschedule(void);
static sem_t _hrt_lock;
static struct work_s _hrt_work;
#include <time.h>
#include <sys/time.h>
#define CLOCK_REALTIME 0
#ifndef CLOCK_MONOTONIC