42 #include <px4_platform_common/posix.h> 59 if (mavlink_log_pub ==
nullptr) {
69 vsnprintf((
char *)log_msg.
text,
sizeof(log_msg.
text), fmt, ap);
72 if (*mavlink_log_pub !=
nullptr) {
static orb_advert_t * mavlink_log_pub
__EXPORT void mavlink_vasprintf(int severity, orb_advert_t *mavlink_log_pub, const char *fmt,...)
High-resolution timer with callouts and timekeeping.
orb_advert_t orb_advertise_queue(const struct orb_metadata *meta, const void *data, unsigned int queue_size)
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).