HAL_PX4: set names on all bus threads

This commit is contained in:
Andrew Tridgell 2016-11-28 10:18:52 +11:00
parent 00ccacb2ab
commit f039a37971
4 changed files with 27 additions and 6 deletions

View File

@ -34,6 +34,24 @@ static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
void *DeviceBus::bus_thread(void *arg)
{
struct DeviceBus *binfo = (struct DeviceBus *)arg;
// setup a name for the thread
char name[] = "XXX:X";
switch (binfo->hal_device->bus_type()) {
case AP_HAL::Device::BUS_TYPE_I2C:
snprintf(name, sizeof(name), "I2C:%u",
binfo->hal_device->bus_num());
break;
case AP_HAL::Device::BUS_TYPE_SPI:
snprintf(name, sizeof(name), "SPI:%u",
binfo->hal_device->bus_num());
break;
default:
break;
}
pthread_setname_np(pthread_self(), name);
while (!_px4_thread_should_exit) {
uint64_t now = AP_HAL::micros64();
DeviceBus::callback_info *callback;
@ -81,7 +99,7 @@ void *DeviceBus::bus_thread(void *arg)
return nullptr;
}
AP_HAL::Device::PeriodicHandle DeviceBus::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
AP_HAL::Device::PeriodicHandle DeviceBus::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb, AP_HAL::Device *_hal_device)
{
if (!thread_started) {
thread_started = true;
@ -95,7 +113,9 @@ AP_HAL::Device::PeriodicHandle DeviceBus::register_periodic_callback(uint32_t pe
param.sched_priority = thread_priority;
(void)pthread_attr_setschedparam(&thread_attr, &param);
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
hal_device = _hal_device;
pthread_create(&thread_ctx, &thread_attr, &DeviceBus::bus_thread, this);
}
DeviceBus::callback_info *callback = new DeviceBus::callback_info;

View File

@ -29,9 +29,9 @@ public:
struct DeviceBus *next;
Semaphore semaphore;
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb);
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb, AP_HAL::Device *hal_device);
static void *bus_thread(void *arg);
private:
struct callback_info {
struct callback_info *next;
@ -42,6 +42,7 @@ private:
uint8_t thread_priority;
pthread_t thread_ctx;
bool thread_started;
AP_HAL::Device *hal_device;
};
}

View File

@ -141,7 +141,7 @@ AP_HAL::Device::PeriodicHandle I2CDevice::register_periodic_callback(uint32_t pe
return nullptr;
}
struct DeviceBus &binfo = businfo[_busnum];
return binfo.register_periodic_callback(period_usec, cb);
return binfo.register_periodic_callback(period_usec, cb, this);
}

View File

@ -223,7 +223,7 @@ AP_HAL::Semaphore *SPIDevice::get_semaphore()
AP_HAL::Device::PeriodicHandle SPIDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
{
return bus.register_periodic_callback(period_usec, cb);
return bus.register_periodic_callback(period_usec, cb, this);
}
bool SPIDevice::adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec)