diff --git a/src/platforms/px4_adc.h b/src/platforms/px4_adc.h index 8420f51971..c8c8ce01f0 100644 --- a/src/platforms/px4_adc.h +++ b/src/platforms/px4_adc.h @@ -52,13 +52,12 @@ // FIXME - this needs to be a px4_adc_msg_s type // Curently copied from NuttX -struct adc_msg_s -{ - uint8_t am_channel; /* The 8-bit ADC Channel */ - int32_t am_data; /* ADC convert result (4 bytes) */ -} __attribute__ ((packed)); +struct adc_msg_s { + uint8_t am_channel; /* The 8-bit ADC Channel */ + int32_t am_data; /* ADC convert result (4 bytes) */ +} __attribute__((packed)); -// Example settings +// Example settings #define ADC_BATTERY_VOLTAGE_CHANNEL 10 #define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1)) #define ADC_AIRSPEED_VOLTAGE_CHANNEL 11 diff --git a/src/platforms/px4_app.h b/src/platforms/px4_app.h index 9aa285e228..df3a8d8294 100644 --- a/src/platforms/px4_app.h +++ b/src/platforms/px4_app.h @@ -40,9 +40,11 @@ #pragma once -namespace px4 { +namespace px4 +{ -class AppState { +class AppState +{ public: ~AppState() {} @@ -65,8 +67,8 @@ protected: bool _isRunning; #endif private: - AppState(const AppState&); - const AppState& operator=(const AppState&); + AppState(const AppState &); + const AppState &operator=(const AppState &); }; } diff --git a/src/platforms/px4_defines.h b/src/platforms/px4_defines.h index 69dc2d64eb..b80532b099 100644 --- a/src/platforms/px4_defines.h +++ b/src/platforms/px4_defines.h @@ -92,7 +92,7 @@ typedef param_t px4_param_t; */ #if defined(__PX4_NUTTX) -#define PX4_ROOTFSDIR +#define PX4_ROOTFSDIR /* XXX this is a hack to resolve conflicts with NuttX headers */ #if !defined(__PX4_TESTS) @@ -119,7 +119,7 @@ typedef param_t px4_param_t; #define PRId64 "lld" #endif -/* +/* * POSIX Specific defines */ #elif defined(__PX4_POSIX) @@ -138,7 +138,7 @@ typedef param_t px4_param_t; /* FIXME - Used to satisfy build */ //STM DocID018909 Rev 8 Sect 39.1 (Unique device ID Register) -#define UNIQUE_ID 0x1FFF7A10 +#define UNIQUE_ID 0x1FFF7A10 #define STM32_SYSMEM_UID "SIMULATIONID" /* FIXME - Used to satisfy build */ @@ -153,12 +153,12 @@ __END_DECLS #endif #define USEC_PER_TICK (1000000UL/PX4_TICKS_PER_SEC) -#define USEC2TICK(x) (((x)+(USEC_PER_TICK/2))/USEC_PER_TICK) +#define USEC2TICK(x) (((x)+(USEC_PER_TICK/2))/USEC_PER_TICK) #define px4_statfs_buf_f_bavail_t unsigned long #if defined(__PX4_QURT) -#define PX4_ROOTFSDIR +#define PX4_ROOTFSDIR #else #define PX4_ROOTFSDIR "rootfs" #endif @@ -166,7 +166,7 @@ __END_DECLS #endif -/* +/* * Defines for ROS and Linux */ #if defined(__PX4_ROS) || defined(__PX4_POSIX) @@ -226,7 +226,7 @@ __END_DECLS #if defined(__PX4_QURT) -#define PX4_ROOTFSDIR +#define PX4_ROOTFSDIR #define DEFAULT_PARAM_FILE "/fs/eeprom/parameters" #define SIOCDEVPRIVATE 999999 @@ -244,7 +244,7 @@ __END_DECLS #endif -/* +/* *Defines for all platforms */ diff --git a/src/platforms/px4_i2c.h b/src/platforms/px4_i2c.h index 2b72f37c5d..1d49600473 100644 --- a/src/platforms/px4_i2c.h +++ b/src/platforms/px4_i2c.h @@ -75,23 +75,23 @@ typedef struct i2c_dev_s px4_i2c_dev_t; // NOTE - This is a copy of the NuttX i2c_msg_s structure typedef struct { - uint16_t addr; /* Slave address */ - uint16_t flags; /* See I2C_M_* definitions */ - uint8_t *buffer; - int length; + uint16_t addr; /* Slave address */ + uint16_t flags; /* See I2C_M_* definitions */ + uint8_t *buffer; + int length; } px4_i2c_msg_t; // NOTE - This is a copy of the NuttX i2c_ops_s structure typedef struct { - const struct px4_i2c_ops_t *ops; /* I2C vtable */ + const struct px4_i2c_ops_t *ops; /* I2C vtable */ } px4_i2c_dev_t; // FIXME - Empty defines for I2C ops // Original version commented out //#define I2C_SETFREQUENCY(d,f) ((d)->ops->setfrequency(d,f)) -#define I2C_SETFREQUENCY(d,f) +#define I2C_SETFREQUENCY(d,f) //#define SPI_SELECT(d,id,s) ((d)->ops->select(d,id,s)) -#define SPI_SELECT(d,id,s) +#define SPI_SELECT(d,id,s) // FIXME - Stub implementation // Original version commented out @@ -101,8 +101,7 @@ inline int I2C_TRANSFER(px4_i2c_dev_t *dev, px4_i2c_msg_t *msg, int count) { ret #ifdef __PX4_QURT -struct i2c_msg -{ +struct i2c_msg { uint16_t addr; /* Slave address */ uint16_t flags; /* See I2C_M_* definitions */ uint8_t *buf; diff --git a/src/platforms/px4_log.h b/src/platforms/px4_log.h index 3dcb29515b..953b766f4d 100644 --- a/src/platforms/px4_log.h +++ b/src/platforms/px4_log.h @@ -178,11 +178,11 @@ __END_DECLS ****************************************************************************/ #define __px4_log_named_cond(name, cond, FMT, ...) \ __px4__log_printcond(cond,\ - "%s " \ - FMT\ - __px4__log_end_fmt \ - ,name, ##__VA_ARGS__\ - ) + "%s " \ + FMT\ + __px4__log_end_fmt \ + ,name, ##__VA_ARGS__\ + ) /**************************************************************************** * __px4_log: @@ -193,11 +193,11 @@ __END_DECLS ****************************************************************************/ #define __px4_log(level, FMT, ...) \ __px4__log_printline(level,\ - __px4__log_level_fmt \ - FMT\ - __px4__log_end_fmt \ - __px4__log_level_arg(level), ##__VA_ARGS__\ - ) + __px4__log_level_fmt \ + FMT\ + __px4__log_end_fmt \ + __px4__log_level_arg(level), ##__VA_ARGS__\ + ) /**************************************************************************** * __px4_log_timestamp: @@ -209,14 +209,14 @@ __END_DECLS ****************************************************************************/ #define __px4_log_timestamp(level, FMT, ...) \ __px4__log_printline(level,\ - __px4__log_level_fmt\ - __px4__log_timestamp_fmt\ - FMT\ - __px4__log_end_fmt\ - __px4__log_level_arg(level)\ - __px4__log_timestamp_arg\ - , ##__VA_ARGS__\ - ) + __px4__log_level_fmt\ + __px4__log_timestamp_fmt\ + FMT\ + __px4__log_end_fmt\ + __px4__log_level_arg(level)\ + __px4__log_timestamp_arg\ + , ##__VA_ARGS__\ + ) /**************************************************************************** * __px4_log_timestamp_thread: @@ -228,16 +228,16 @@ __END_DECLS ****************************************************************************/ #define __px4_log_timestamp_thread(level, FMT, ...) \ __px4__log_printline(level,\ - __px4__log_level_fmt\ - __px4__log_timestamp_fmt\ - __px4__log_thread_fmt\ - FMT\ - __px4__log_end_fmt\ - __px4__log_level_arg(level)\ - __px4__log_timestamp_arg\ - __px4__log_thread_arg\ - , ##__VA_ARGS__\ - ) + __px4__log_level_fmt\ + __px4__log_timestamp_fmt\ + __px4__log_thread_fmt\ + FMT\ + __px4__log_end_fmt\ + __px4__log_level_arg(level)\ + __px4__log_timestamp_arg\ + __px4__log_thread_arg\ + , ##__VA_ARGS__\ + ) /**************************************************************************** * __px4_log_file_and_line: @@ -249,16 +249,16 @@ __END_DECLS ****************************************************************************/ #define __px4_log_file_and_line(level, FMT, ...) \ __px4__log_printline(level,\ - __px4__log_level_fmt\ - __px4__log_timestamp_fmt\ - FMT\ - __px4__log_file_and_line_fmt\ - __px4__log_end_fmt\ - __px4__log_level_arg(level)\ - __px4__log_timestamp_arg\ - , ##__VA_ARGS__\ - __px4__log_file_and_line_arg\ - ) + __px4__log_level_fmt\ + __px4__log_timestamp_fmt\ + FMT\ + __px4__log_file_and_line_fmt\ + __px4__log_end_fmt\ + __px4__log_level_arg(level)\ + __px4__log_timestamp_arg\ + , ##__VA_ARGS__\ + __px4__log_file_and_line_arg\ + ) /**************************************************************************** * __px4_log_timestamp_file_and_line: @@ -271,16 +271,16 @@ __END_DECLS ****************************************************************************/ #define __px4_log_timestamp_file_and_line(level, FMT, ...) \ __px4__log_printline(level,\ - __px4__log_level_fmt\ - __px4__log_timestamp_fmt\ - FMT\ - __px4__log_file_and_line_fmt\ - __px4__log_end_fmt\ - __px4__log_level_arg(level)\ - __px4__log_timestamp_arg\ - , ##__VA_ARGS__\ - __px4__log_file_and_line_arg\ - ) + __px4__log_level_fmt\ + __px4__log_timestamp_fmt\ + FMT\ + __px4__log_file_and_line_fmt\ + __px4__log_end_fmt\ + __px4__log_level_arg(level)\ + __px4__log_timestamp_arg\ + , ##__VA_ARGS__\ + __px4__log_file_and_line_arg\ + ) /**************************************************************************** * __px4_log_thread_file_and_line: @@ -293,16 +293,16 @@ __END_DECLS ****************************************************************************/ #define __px4_log_thread_file_and_line(level, FMT, ...) \ __px4__log_printline(level,\ - __px4__log_level_fmt\ - __px4__log_thread_fmt\ - FMT\ - __px4__log_file_and_line_fmt\ - __px4__log_end_fmt\ - __px4__log_level_arg(level)\ - __px4__log_thread_arg\ - , ##__VA_ARGS__\ - __px4__log_file_and_line_arg\ - ) + __px4__log_level_fmt\ + __px4__log_thread_fmt\ + FMT\ + __px4__log_file_and_line_fmt\ + __px4__log_end_fmt\ + __px4__log_level_arg(level)\ + __px4__log_thread_arg\ + , ##__VA_ARGS__\ + __px4__log_file_and_line_arg\ + ) /**************************************************************************** * __px4_log_timestamp_thread_file_and_line: @@ -315,18 +315,18 @@ __END_DECLS ****************************************************************************/ #define __px4_log_timestamp_thread_file_and_line(level, FMT, ...) \ __px4__log_printline(level,\ - __px4__log_level_fmt\ - __px4__log_timestamp_fmt\ - __px4__log_thread_fmt\ - FMT\ - __px4__log_file_and_line_fmt\ - __px4__log_end_fmt\ - __px4__log_level_arg(level)\ - __px4__log_timestamp_arg\ - __px4__log_thread_arg\ - , ##__VA_ARGS__\ - __px4__log_file_and_line_arg\ - ) + __px4__log_level_fmt\ + __px4__log_timestamp_fmt\ + __px4__log_thread_fmt\ + FMT\ + __px4__log_file_and_line_fmt\ + __px4__log_end_fmt\ + __px4__log_level_arg(level)\ + __px4__log_timestamp_arg\ + __px4__log_thread_arg\ + , ##__VA_ARGS__\ + __px4__log_file_and_line_arg\ + ) /**************************************************************************** diff --git a/src/platforms/px4_nodehandle.h b/src/platforms/px4_nodehandle.h index 497f3be04c..dc806aa905 100644 --- a/src/platforms/px4_nodehandle.h +++ b/src/platforms/px4_nodehandle.h @@ -86,7 +86,7 @@ public: template Subscriber *subscribe(void(*fp)(const T &), unsigned interval) { - SubscriberBase *sub = new SubscriberROS((ros::NodeHandle*)this, std::bind(fp, std::placeholders::_1)); + SubscriberBase *sub = new SubscriberROS((ros::NodeHandle *)this, std::bind(fp, std::placeholders::_1)); _subs.push_back(sub); return (Subscriber *)sub; } @@ -99,7 +99,7 @@ public: template Subscriber *subscribe(void(C::*fp)(const T &), C *obj, unsigned interval) { - SubscriberBase *sub = new SubscriberROS((ros::NodeHandle*)this, std::bind(fp, obj, std::placeholders::_1)); + SubscriberBase *sub = new SubscriberROS((ros::NodeHandle *)this, std::bind(fp, obj, std::placeholders::_1)); _subs.push_back(sub); return (Subscriber *)sub; } @@ -110,7 +110,7 @@ public: template Subscriber *subscribe(unsigned interval) { - SubscriberBase *sub = new SubscriberROS((ros::NodeHandle*)this); + SubscriberBase *sub = new SubscriberROS((ros::NodeHandle *)this); _subs.push_back(sub); return (Subscriber *)sub; } @@ -119,11 +119,11 @@ public: * Advertise topic */ template - Publisher* advertise() + Publisher *advertise() { - PublisherROS *pub = new PublisherROS((ros::NodeHandle*)this); - _pubs.push_back((PublisherBase*)pub); - return (Publisher*)pub; + PublisherROS *pub = new PublisherROS((ros::NodeHandle *)this); + _pubs.push_back((PublisherBase *)pub); + return (Publisher *)pub; } /** @@ -242,7 +242,7 @@ public: { PublisherUORB *pub = new PublisherUORB(); _pubs.add(pub); - return (Publisher*)pub; + return (Publisher *)pub; } /** diff --git a/src/platforms/px4_posix.h b/src/platforms/px4_posix.h index bd682d9ce5..ab53d03900 100644 --- a/src/platforms/px4_posix.h +++ b/src/platforms/px4_posix.h @@ -54,8 +54,7 @@ __BEGIN_DECLS -typedef struct -{ +typedef struct { pthread_mutex_t lock; pthread_cond_t wait; int value; @@ -97,7 +96,7 @@ typedef struct pollfd px4_pollfd_struct_t; #if defined(__cplusplus) #define _GLOBAL :: #else -#define _GLOBAL +#define _GLOBAL #endif #define px4_open _GLOBAL open #define px4_close _GLOBAL close @@ -118,14 +117,14 @@ typedef struct pollfd px4_pollfd_struct_t; typedef short pollevent_t; typedef struct { - /* This part of the struct is POSIX-like */ - int fd; /* The descriptor being polled */ - pollevent_t events; /* The input event flags */ - pollevent_t revents; /* The output event flags */ + /* This part of the struct is POSIX-like */ + int fd; /* The descriptor being polled */ + pollevent_t events; /* The input event flags */ + pollevent_t revents; /* The output event flags */ - /* Required for PX4 compatability */ - px4_sem_t *sem; /* Pointer to semaphore used to post output event */ - void *priv; /* For use by drivers */ + /* Required for PX4 compatability */ + px4_sem_t *sem; /* Pointer to semaphore used to post output event */ + void *priv; /* For use by drivers */ } px4_pollfd_struct_t; __BEGIN_DECLS @@ -150,8 +149,8 @@ extern int px4_errno; __EXPORT void px4_show_devices(void); __EXPORT void px4_show_files(void); -__EXPORT const char * px4_get_device_names(unsigned int *handle); +__EXPORT const char *px4_get_device_names(unsigned int *handle); __EXPORT void px4_show_topics(void); -__EXPORT const char * px4_get_topic_names(unsigned int *handle); +__EXPORT const char *px4_get_topic_names(unsigned int *handle); __END_DECLS diff --git a/src/platforms/px4_publisher.h b/src/platforms/px4_publisher.h index eb8e964e79..fb9ec50e10 100644 --- a/src/platforms/px4_publisher.h +++ b/src/platforms/px4_publisher.h @@ -86,7 +86,8 @@ public: */ PublisherROS(ros::NodeHandle *rnh) : Publisher(), - _ros_pub(rnh->advertisedata())>::type &>(T::handle(), kQueueSizeDefault)) + _ros_pub(rnh->advertise < typename std::remove_reference < decltype(((T *)nullptr)->data()) >::type & > (T::handle(), + kQueueSizeDefault)) {} ~PublisherROS() {}; @@ -136,7 +137,8 @@ public: _uorb_pub(new uORB::PublicationBase(T::handle())) {} - ~PublisherUORB() { + ~PublisherUORB() + { delete _uorb_pub; }; @@ -145,7 +147,7 @@ public: */ int publish(const T &msg) { - _uorb_pub->update((void *)&(msg.data())); + _uorb_pub->update((void *) & (msg.data())); return 0; } @@ -154,7 +156,7 @@ public: */ void update() {} ; private: - uORB::PublicationBase * _uorb_pub; /**< Handle to the publisher */ + uORB::PublicationBase *_uorb_pub; /**< Handle to the publisher */ }; #endif diff --git a/src/platforms/px4_spi.h b/src/platforms/px4_spi.h index 17397ee7ac..78b747b775 100644 --- a/src/platforms/px4_spi.h +++ b/src/platforms/px4_spi.h @@ -3,32 +3,29 @@ #ifdef __PX4_NUTTX #include #elif defined(__PX4_POSIX) -enum spi_dev_e -{ - SPIDEV_NONE = 0, /* Not a valid value */ - SPIDEV_MMCSD, /* Select SPI MMC/SD device */ - SPIDEV_FLASH, /* Select SPI FLASH device */ - SPIDEV_ETHERNET, /* Select SPI ethernet device */ - SPIDEV_DISPLAY, /* Select SPI LCD/OLED display device */ - SPIDEV_WIRELESS, /* Select SPI Wireless device */ - SPIDEV_TOUCHSCREEN, /* Select SPI touchscreen device */ - SPIDEV_EXPANDER, /* Select SPI I/O expander device */ - SPIDEV_MUX, /* Select SPI multiplexer device */ - SPIDEV_AUDIO_DATA, /* Select SPI audio codec device data port */ - SPIDEV_AUDIO_CTRL, /* Select SPI audio codec device control port */ +enum spi_dev_e { + SPIDEV_NONE = 0, /* Not a valid value */ + SPIDEV_MMCSD, /* Select SPI MMC/SD device */ + SPIDEV_FLASH, /* Select SPI FLASH device */ + SPIDEV_ETHERNET, /* Select SPI ethernet device */ + SPIDEV_DISPLAY, /* Select SPI LCD/OLED display device */ + SPIDEV_WIRELESS, /* Select SPI Wireless device */ + SPIDEV_TOUCHSCREEN, /* Select SPI touchscreen device */ + SPIDEV_EXPANDER, /* Select SPI I/O expander device */ + SPIDEV_MUX, /* Select SPI multiplexer device */ + SPIDEV_AUDIO_DATA, /* Select SPI audio codec device data port */ + SPIDEV_AUDIO_CTRL, /* Select SPI audio codec device control port */ }; /* Certain SPI devices may required differnt clocking modes */ -enum spi_mode_e -{ - SPIDEV_MODE0 = 0, /* CPOL=0 CHPHA=0 */ - SPIDEV_MODE1, /* CPOL=0 CHPHA=1 */ - SPIDEV_MODE2, /* CPOL=1 CHPHA=0 */ - SPIDEV_MODE3 /* CPOL=1 CHPHA=1 */ +enum spi_mode_e { + SPIDEV_MODE0 = 0, /* CPOL=0 CHPHA=0 */ + SPIDEV_MODE1, /* CPOL=0 CHPHA=1 */ + SPIDEV_MODE2, /* CPOL=1 CHPHA=0 */ + SPIDEV_MODE3 /* CPOL=1 CHPHA=1 */ }; -struct spi_dev_s -{ +struct spi_dev_s { int unused; }; #else diff --git a/src/platforms/px4_subscriber.h b/src/platforms/px4_subscriber.h index e92c82fc66..59cfa5a191 100644 --- a/src/platforms/px4_subscriber.h +++ b/src/platforms/px4_subscriber.h @@ -86,12 +86,12 @@ public: /** * Get the last message value */ - virtual T& get() {return _msg_current;} + virtual T &get() {return _msg_current;} /** * Get the last native message value */ - virtual decltype(((T*)nullptr)->data()) data() + virtual decltype(((T *)nullptr)->data()) data() { return _msg_current.data(); } @@ -135,7 +135,7 @@ protected: * Called on topic update, saves the current message and then calls the provided callback function * needs to use the native type as it is called by ROS */ - void callback(const typename std::remove_referencedata())>::type &msg) + void callback(const typename std::remove_reference < decltype(((T *)nullptr)->data()) >::type &msg) { /* Store data */ this->_msg_current.data() = msg; @@ -197,7 +197,8 @@ public: _uorb_sub(new uORB::SubscriptionBase(T::handle(), interval)) {} - virtual ~SubscriberUORB() { + virtual ~SubscriberUORB() + { delete _uorb_sub; }; @@ -219,19 +220,19 @@ public: int getUORBHandle() { return _uorb_sub->getHandle(); } protected: - uORB::SubscriptionBase * _uorb_sub; /**< Handle to the subscription */ + uORB::SubscriptionBase *_uorb_sub; /**< Handle to the subscription */ #ifndef CONFIG_ARCH_BOARD_SIM - typename std::remove_referencedata())>::type getUORBData() + typename std::remove_reference < decltype(((T *)nullptr)->data()) >::type getUORBData() { - return (typename std::remove_referencedata())>::type)*_uorb_sub; + return (typename std::remove_reference < decltype(((T *)nullptr)->data()) >::type) * _uorb_sub; } #endif /** * Get void pointer to last message value */ - void *get_void_ptr() { return (void *)&(this->_msg_current.data()); } + void *get_void_ptr() { return (void *) & (this->_msg_current.data()); } }; @@ -248,9 +249,9 @@ public: */ SubscriberUORBCallback(unsigned interval #ifndef CONFIG_ARCH_BOARD_SIM - ,std::function cbf) + , std::function cbf) #else - ) + ) #endif : SubscriberUORB(interval), diff --git a/src/platforms/px4_tasks.h b/src/platforms/px4_tasks.h index 9dc237e63b..04585aaced 100644 --- a/src/platforms/px4_tasks.h +++ b/src/platforms/px4_tasks.h @@ -105,11 +105,11 @@ __EXPORT void px4_systemreset(bool to_bootloader) noreturn_function; /** Starts a task and performs any specific accounting, scheduler setup, etc. */ __EXPORT px4_task_t px4_task_spawn_cmd(const char *name, - int priority, - int scheduler, - int stack_size, - px4_main_t entry, - char * const argv[]); + int priority, + int scheduler, + int stack_size, + px4_main_t entry, + char *const argv[]); /** Deletes a task - does not do resource cleanup **/ __EXPORT int px4_task_delete(px4_task_t pid); diff --git a/src/platforms/px4_time.h b/src/platforms/px4_time.h index 22751b3a99..d57f8e9103 100644 --- a/src/platforms/px4_time.h +++ b/src/platforms/px4_time.h @@ -30,8 +30,7 @@ __BEGIN_DECLS #if 0 #if !defined(__cplusplus) -struct timespec -{ +struct timespec { time_t tv_sec; long tv_nsec; }; diff --git a/src/platforms/px4_workqueue.h b/src/platforms/px4_workqueue.h index 76e1218ba5..3e3170f2de 100644 --- a/src/platforms/px4_workqueue.h +++ b/src/platforms/px4_workqueue.h @@ -48,7 +48,7 @@ #include #ifdef __PX4_QURT - #include +#include #endif __BEGIN_DECLS @@ -57,10 +57,9 @@ __BEGIN_DECLS #define LPWORK 1 #define NWORKERS 2 -struct wqueue_s -{ - pid_t pid; /* The task ID of the worker thread */ - struct dq_queue_s q; /* The queue of pending work */ +struct wqueue_s { + pid_t pid; /* The task ID of the worker thread */ + struct dq_queue_s q; /* The queue of pending work */ }; extern struct wqueue_s g_work[NWORKERS]; @@ -69,13 +68,12 @@ extern struct wqueue_s g_work[NWORKERS]; typedef void (*worker_t)(void *arg); -struct work_s -{ - struct dq_entry_s dq; /* Implements a doubly linked list */ - worker_t worker; /* Work callback */ - void *arg; /* Callback argument */ - uint64_t qtime; /* Time work queued */ - uint32_t delay; /* Delay until work performed */ +struct work_s { + struct dq_entry_s dq; /* Implements a doubly linked list */ + worker_t worker; /* Work callback */ + void *arg; /* Callback argument */ + uint64_t qtime; /* Time work queued */ + uint32_t delay; /* Delay until work performed */ }; /**************************************************************************** @@ -144,6 +142,6 @@ int work_lpthread(int argc, char *argv[]); __END_DECLS -#else +#else #error "Unknown target OS" #endif