mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
HAL_ChibiOS: shorted thread names
changes names so threads can be distinguished by first 4 bytes
This commit is contained in:
parent
a25ea5addc
commit
09477b2dfe
@ -104,12 +104,12 @@ AP_HAL::Device::PeriodicHandle DeviceBus::register_periodic_callback(uint32_t pe
|
||||
char *name = (char *)malloc(name_len);
|
||||
switch (hal_device->bus_type()) {
|
||||
case AP_HAL::Device::BUS_TYPE_I2C:
|
||||
snprintf(name, name_len, "I2C:%u",
|
||||
snprintf(name, name_len, "I2C%u",
|
||||
hal_device->bus_num());
|
||||
break;
|
||||
|
||||
case AP_HAL::Device::BUS_TYPE_SPI:
|
||||
snprintf(name, name_len, "SPI:%u",
|
||||
snprintf(name, name_len, "SPI%u",
|
||||
hal_device->bus_num());
|
||||
break;
|
||||
default:
|
||||
|
@ -307,7 +307,7 @@ void Scheduler::_run_timers()
|
||||
void Scheduler::_timer_thread(void *arg)
|
||||
{
|
||||
Scheduler *sched = (Scheduler *)arg;
|
||||
chRegSetThreadName("apm_timer");
|
||||
chRegSetThreadName("timer");
|
||||
|
||||
while (!sched->_hal_initialized) {
|
||||
sched->delay_microseconds(1000);
|
||||
@ -346,7 +346,7 @@ bool Scheduler::in_expected_delay(void) const
|
||||
void Scheduler::_monitor_thread(void *arg)
|
||||
{
|
||||
Scheduler *sched = (Scheduler *)arg;
|
||||
chRegSetThreadName("apm_monitor");
|
||||
chRegSetThreadName("monitor");
|
||||
|
||||
while (!sched->_initialized) {
|
||||
sched->delay(100);
|
||||
@ -389,7 +389,7 @@ void Scheduler::_monitor_thread(void *arg)
|
||||
void Scheduler::_rcin_thread(void *arg)
|
||||
{
|
||||
Scheduler *sched = (Scheduler *)arg;
|
||||
chRegSetThreadName("apm_rcin");
|
||||
chRegSetThreadName("rcin");
|
||||
while (!sched->_hal_initialized) {
|
||||
sched->delay_microseconds(20000);
|
||||
}
|
||||
@ -423,7 +423,7 @@ void Scheduler::_run_io(void)
|
||||
void Scheduler::_io_thread(void* arg)
|
||||
{
|
||||
Scheduler *sched = (Scheduler *)arg;
|
||||
chRegSetThreadName("apm_io");
|
||||
chRegSetThreadName("io");
|
||||
while (!sched->_hal_initialized) {
|
||||
sched->delay_microseconds(1000);
|
||||
}
|
||||
@ -449,7 +449,7 @@ void Scheduler::_io_thread(void* arg)
|
||||
void Scheduler::_storage_thread(void* arg)
|
||||
{
|
||||
Scheduler *sched = (Scheduler *)arg;
|
||||
chRegSetThreadName("apm_storage");
|
||||
chRegSetThreadName("storage");
|
||||
while (!sched->_hal_initialized) {
|
||||
sched->delay_microseconds(10000);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user