Browse Source

HAL_ChibiOS: shorted thread names

changes names so threads can be distinguished by first 4 bytes
c415-sdk
Andrew Tridgell 5 years ago
parent
commit
09477b2dfe
  1. 4
      libraries/AP_HAL_ChibiOS/Device.cpp
  2. 10
      libraries/AP_HAL_ChibiOS/Scheduler.cpp

4
libraries/AP_HAL_ChibiOS/Device.cpp

@ -104,12 +104,12 @@ AP_HAL::Device::PeriodicHandle DeviceBus::register_periodic_callback(uint32_t pe
char *name = (char *)malloc(name_len); char *name = (char *)malloc(name_len);
switch (hal_device->bus_type()) { switch (hal_device->bus_type()) {
case AP_HAL::Device::BUS_TYPE_I2C: case AP_HAL::Device::BUS_TYPE_I2C:
snprintf(name, name_len, "I2C:%u", snprintf(name, name_len, "I2C%u",
hal_device->bus_num()); hal_device->bus_num());
break; break;
case AP_HAL::Device::BUS_TYPE_SPI: case AP_HAL::Device::BUS_TYPE_SPI:
snprintf(name, name_len, "SPI:%u", snprintf(name, name_len, "SPI%u",
hal_device->bus_num()); hal_device->bus_num());
break; break;
default: default:

10
libraries/AP_HAL_ChibiOS/Scheduler.cpp

@ -307,7 +307,7 @@ void Scheduler::_run_timers()
void Scheduler::_timer_thread(void *arg) void Scheduler::_timer_thread(void *arg)
{ {
Scheduler *sched = (Scheduler *)arg; Scheduler *sched = (Scheduler *)arg;
chRegSetThreadName("apm_timer"); chRegSetThreadName("timer");
while (!sched->_hal_initialized) { while (!sched->_hal_initialized) {
sched->delay_microseconds(1000); sched->delay_microseconds(1000);
@ -346,7 +346,7 @@ bool Scheduler::in_expected_delay(void) const
void Scheduler::_monitor_thread(void *arg) void Scheduler::_monitor_thread(void *arg)
{ {
Scheduler *sched = (Scheduler *)arg; Scheduler *sched = (Scheduler *)arg;
chRegSetThreadName("apm_monitor"); chRegSetThreadName("monitor");
while (!sched->_initialized) { while (!sched->_initialized) {
sched->delay(100); sched->delay(100);
@ -389,7 +389,7 @@ void Scheduler::_monitor_thread(void *arg)
void Scheduler::_rcin_thread(void *arg) void Scheduler::_rcin_thread(void *arg)
{ {
Scheduler *sched = (Scheduler *)arg; Scheduler *sched = (Scheduler *)arg;
chRegSetThreadName("apm_rcin"); chRegSetThreadName("rcin");
while (!sched->_hal_initialized) { while (!sched->_hal_initialized) {
sched->delay_microseconds(20000); sched->delay_microseconds(20000);
} }
@ -423,7 +423,7 @@ void Scheduler::_run_io(void)
void Scheduler::_io_thread(void* arg) void Scheduler::_io_thread(void* arg)
{ {
Scheduler *sched = (Scheduler *)arg; Scheduler *sched = (Scheduler *)arg;
chRegSetThreadName("apm_io"); chRegSetThreadName("io");
while (!sched->_hal_initialized) { while (!sched->_hal_initialized) {
sched->delay_microseconds(1000); sched->delay_microseconds(1000);
} }
@ -449,7 +449,7 @@ void Scheduler::_io_thread(void* arg)
void Scheduler::_storage_thread(void* arg) void Scheduler::_storage_thread(void* arg)
{ {
Scheduler *sched = (Scheduler *)arg; Scheduler *sched = (Scheduler *)arg;
chRegSetThreadName("apm_storage"); chRegSetThreadName("storage");
while (!sched->_hal_initialized) { while (!sched->_hal_initialized) {
sched->delay_microseconds(10000); sched->delay_microseconds(10000);
} }

Loading…
Cancel
Save