17 #include <arch/board/board.h> 18 #include "board_config.h" 39 char name[] =
"XXX:XX";
42 snprintf(name,
sizeof(name),
"I2C:%u",
47 snprintf(name,
sizeof(name),
"SPI:%u",
53 pthread_setname_np(pthread_self(), name);
60 for (callback = binfo->
callbacks; callback; callback = callback->
next) {
74 uint64_t next_needed = 0;
77 for (callback = binfo->
callbacks; callback; callback = callback->
next) {
78 if (next_needed == 0 ||
81 if (next_needed < now) {
88 uint32_t
delay = 50000;
89 if (next_needed >= now && next_needed - now < delay) {
90 delay = next_needed - now;
107 pthread_attr_t thread_attr;
108 struct sched_param param;
110 pthread_attr_init(&thread_attr);
111 pthread_attr_setstacksize(&thread_attr, 1024);
114 (void)pthread_attr_setschedparam(&thread_attr, ¶m);
115 pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
122 if (callback ==
nullptr) {
142 if (!pthread_equal(pthread_self(),
thread_ctx)) {
143 fprintf(stderr,
"can't adjust timer from unknown thread context\n");
AP_HAL::Device::PeriodicCb cb
bool adjust_timer(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec)
bool take(uint32_t timeout_ms)
AP_HAL::Device * hal_device
#define HAL_SEMAPHORE_BLOCK_FOREVER
uint8_t bus_num(void) const
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb, AP_HAL::Device *hal_device)
struct callback_info * next
enum BusType bus_type(void) const
bool _px4_thread_should_exit
virtual void delay_microseconds(uint16_t us)=0
int snprintf(char *str, size_t size, const char *fmt,...)
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
struct PX4::DeviceBus::callback_info * callbacks
static void * bus_thread(void *arg)
AP_HAL::Scheduler * scheduler
static const AP_HAL::HAL & hal