mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_ESP32: bugfixes
bump tick rate to 1kz to match chibios experimentally make delay_microseconds not delay, and only yield ( vTaskDelay yields to higher-priority tasks ) ESP32 disable all watchdogs emit info to console to tell user where to connect tcp/udp and what ports comment out bad code throwing a ptr error
This commit is contained in:
parent
24de88f85c
commit
73afd26465
@ -231,7 +231,7 @@ void Scheduler::delay(uint16_t ms)
|
|||||||
|
|
||||||
void Scheduler::delay_microseconds(uint16_t us)
|
void Scheduler::delay_microseconds(uint16_t us)
|
||||||
{
|
{
|
||||||
if (us < 100) {
|
if (in_main_thread() && us < 100) {
|
||||||
ets_delay_us(us);
|
ets_delay_us(us);
|
||||||
} else { // Minimum delay for FreeRTOS is 1ms
|
} else { // Minimum delay for FreeRTOS is 1ms
|
||||||
uint32_t tick = portTICK_PERIOD_MS * 1000;
|
uint32_t tick = portTICK_PERIOD_MS * 1000;
|
||||||
@ -548,10 +548,10 @@ void Scheduler::print_main_loop_rate(void)
|
|||||||
static int64_t last_run = 0;
|
static int64_t last_run = 0;
|
||||||
if (AP_HAL::millis64() - last_run > 10000) {
|
if (AP_HAL::millis64() - last_run > 10000) {
|
||||||
last_run = AP_HAL::millis64();
|
last_run = AP_HAL::millis64();
|
||||||
const float actual_loop_rate = AP::scheduler().get_filtered_loop_rate_hz();
|
// null pointer in here...
|
||||||
const uint16_t expected_loop_rate = AP::scheduler().get_loop_rate_hz();
|
//const float actual_loop_rate = AP::scheduler().get_filtered_loop_rate_hz();
|
||||||
hal.console->printf("loop_rate: actual: %uHz, expected: %uHz\n",
|
//const uint16_t expected_loop_rate = AP::scheduler().get_loop_rate_hz();
|
||||||
(uint16_t)actual_loop_rate, (uint16_t)expected_loop_rate);
|
//hal.console->printf("loop_rate: actual: %uHz, expected: %uHz\n",
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -59,7 +59,7 @@ void WiFiDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||||||
if (xTaskCreatePinnedToCore(_wifi_thread, "APM_WIFI1", Scheduler::WIFI_SS1, this, Scheduler::WIFI_PRIO1, &_wifi_task_handle,FASTCPU) != pdPASS) {
|
if (xTaskCreatePinnedToCore(_wifi_thread, "APM_WIFI1", Scheduler::WIFI_SS1, this, Scheduler::WIFI_PRIO1, &_wifi_task_handle,FASTCPU) != pdPASS) {
|
||||||
hal.console->printf("FAILED to create task _wifi_thread on FASTCPU\n");
|
hal.console->printf("FAILED to create task _wifi_thread on FASTCPU\n");
|
||||||
} else {
|
} else {
|
||||||
hal.console->printf("OK created task _wifi_thread on FASTCPU\n");
|
hal.console->printf("OK created task _wifi_thread for TCP with PORT 5760 on FASTCPU\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
_readbuf.set_size(RX_BUF_SIZE);
|
_readbuf.set_size(RX_BUF_SIZE);
|
||||||
|
@ -62,7 +62,7 @@ void WiFiUdpDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||||||
if (xTaskCreatePinnedToCore(_wifi_thread2, "APM_WIFI2", Scheduler::WIFI_SS2, this, Scheduler::WIFI_PRIO2, &_wifi_task_handle,FASTCPU) != pdPASS) {
|
if (xTaskCreatePinnedToCore(_wifi_thread2, "APM_WIFI2", Scheduler::WIFI_SS2, this, Scheduler::WIFI_PRIO2, &_wifi_task_handle,FASTCPU) != pdPASS) {
|
||||||
hal.console->printf("FAILED to create task _wifi_thread2 on FASTCPU\n");
|
hal.console->printf("FAILED to create task _wifi_thread2 on FASTCPU\n");
|
||||||
} else {
|
} else {
|
||||||
hal.console->printf("OK created task _wifi_thread2 on FASTCPU\n");
|
hal.console->printf("OK created task _wifi_thread2 for UDP on port 14550 on FASTCPU\n"); //UDP_PORT
|
||||||
}
|
}
|
||||||
|
|
||||||
_readbuf.set_size(RX_BUF_SIZE);
|
_readbuf.set_size(RX_BUF_SIZE);
|
||||||
|
@ -56,7 +56,7 @@ CONFIG_BOOTLOADER_VDDSDIO_BOOST_1_9V=y
|
|||||||
# CONFIG_BOOTLOADER_FACTORY_RESET is not set
|
# CONFIG_BOOTLOADER_FACTORY_RESET is not set
|
||||||
# CONFIG_BOOTLOADER_APP_TEST is not set
|
# CONFIG_BOOTLOADER_APP_TEST is not set
|
||||||
CONFIG_BOOTLOADER_REGION_PROTECTION_ENABLE=y
|
CONFIG_BOOTLOADER_REGION_PROTECTION_ENABLE=y
|
||||||
CONFIG_BOOTLOADER_WDT_ENABLE=y
|
CONFIG_BOOTLOADER_WDT_ENABLE=n
|
||||||
# CONFIG_BOOTLOADER_WDT_DISABLE_IN_USER_CODE is not set
|
# CONFIG_BOOTLOADER_WDT_DISABLE_IN_USER_CODE is not set
|
||||||
CONFIG_BOOTLOADER_WDT_TIME_MS=9000
|
CONFIG_BOOTLOADER_WDT_TIME_MS=9000
|
||||||
# CONFIG_BOOTLOADER_APP_ROLLBACK_ENABLE is not set
|
# CONFIG_BOOTLOADER_APP_ROLLBACK_ENABLE is not set
|
||||||
@ -455,10 +455,10 @@ CONFIG_ESP_CONSOLE_UART=y
|
|||||||
CONFIG_ESP_CONSOLE_MULTIPLE_UART=y
|
CONFIG_ESP_CONSOLE_MULTIPLE_UART=y
|
||||||
CONFIG_ESP_CONSOLE_UART_NUM=0
|
CONFIG_ESP_CONSOLE_UART_NUM=0
|
||||||
CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200
|
CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200
|
||||||
CONFIG_ESP_INT_WDT=y
|
CONFIG_ESP_INT_WDT=n
|
||||||
CONFIG_ESP_INT_WDT_TIMEOUT_MS=1000
|
CONFIG_ESP_INT_WDT_TIMEOUT_MS=1000
|
||||||
CONFIG_ESP_INT_WDT_CHECK_CPU1=y
|
CONFIG_ESP_INT_WDT_CHECK_CPU1=y
|
||||||
CONFIG_ESP_TASK_WDT=y
|
CONFIG_ESP_TASK_WDT=n
|
||||||
# CONFIG_ESP_TASK_WDT_PANIC is not set
|
# CONFIG_ESP_TASK_WDT_PANIC is not set
|
||||||
CONFIG_ESP_TASK_WDT_TIMEOUT_S=5
|
CONFIG_ESP_TASK_WDT_TIMEOUT_S=5
|
||||||
CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
|
CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
|
||||||
@ -579,7 +579,7 @@ CONFIG_FREERTOS_TICK_SUPPORT_CORETIMER=y
|
|||||||
# CONFIG_FREERTOS_CORETIMER_0 is not set
|
# CONFIG_FREERTOS_CORETIMER_0 is not set
|
||||||
CONFIG_FREERTOS_CORETIMER_1=y
|
CONFIG_FREERTOS_CORETIMER_1=y
|
||||||
CONFIG_FREERTOS_SYSTICK_USES_CCOUNT=y
|
CONFIG_FREERTOS_SYSTICK_USES_CCOUNT=y
|
||||||
CONFIG_FREERTOS_HZ=500
|
CONFIG_FREERTOS_HZ=1000
|
||||||
CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION=y
|
CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION=y
|
||||||
# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_NONE is not set
|
# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_NONE is not set
|
||||||
# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_PTRVAL is not set
|
# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_PTRVAL is not set
|
||||||
@ -1150,10 +1150,10 @@ CONFIG_CONSOLE_UART_DEFAULT=y
|
|||||||
CONFIG_CONSOLE_UART=y
|
CONFIG_CONSOLE_UART=y
|
||||||
CONFIG_CONSOLE_UART_NUM=0
|
CONFIG_CONSOLE_UART_NUM=0
|
||||||
CONFIG_CONSOLE_UART_BAUDRATE=115200
|
CONFIG_CONSOLE_UART_BAUDRATE=115200
|
||||||
CONFIG_INT_WDT=y
|
CONFIG_INT_WDT=n
|
||||||
CONFIG_INT_WDT_TIMEOUT_MS=1000
|
CONFIG_INT_WDT_TIMEOUT_MS=1000
|
||||||
CONFIG_INT_WDT_CHECK_CPU1=y
|
CONFIG_INT_WDT_CHECK_CPU1=y
|
||||||
CONFIG_TASK_WDT=y
|
CONFIG_TASK_WDT=n
|
||||||
# CONFIG_TASK_WDT_PANIC is not set
|
# CONFIG_TASK_WDT_PANIC is not set
|
||||||
CONFIG_TASK_WDT_TIMEOUT_S=5
|
CONFIG_TASK_WDT_TIMEOUT_S=5
|
||||||
CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
|
CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
|
||||||
|
@ -55,7 +55,7 @@ CONFIG_BOOTLOADER_VDDSDIO_BOOST_1_9V=y
|
|||||||
# CONFIG_BOOTLOADER_FACTORY_RESET is not set
|
# CONFIG_BOOTLOADER_FACTORY_RESET is not set
|
||||||
# CONFIG_BOOTLOADER_APP_TEST is not set
|
# CONFIG_BOOTLOADER_APP_TEST is not set
|
||||||
CONFIG_BOOTLOADER_REGION_PROTECTION_ENABLE=y
|
CONFIG_BOOTLOADER_REGION_PROTECTION_ENABLE=y
|
||||||
CONFIG_BOOTLOADER_WDT_ENABLE=y
|
CONFIG_BOOTLOADER_WDT_ENABLE=n
|
||||||
# CONFIG_BOOTLOADER_WDT_DISABLE_IN_USER_CODE is not set
|
# CONFIG_BOOTLOADER_WDT_DISABLE_IN_USER_CODE is not set
|
||||||
CONFIG_BOOTLOADER_WDT_TIME_MS=9000
|
CONFIG_BOOTLOADER_WDT_TIME_MS=9000
|
||||||
# CONFIG_BOOTLOADER_APP_ROLLBACK_ENABLE is not set
|
# CONFIG_BOOTLOADER_APP_ROLLBACK_ENABLE is not set
|
||||||
@ -437,10 +437,10 @@ CONFIG_ESP_CONSOLE_UART=y
|
|||||||
CONFIG_ESP_CONSOLE_MULTIPLE_UART=y
|
CONFIG_ESP_CONSOLE_MULTIPLE_UART=y
|
||||||
CONFIG_ESP_CONSOLE_UART_NUM=0
|
CONFIG_ESP_CONSOLE_UART_NUM=0
|
||||||
CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200
|
CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200
|
||||||
CONFIG_ESP_INT_WDT=y
|
CONFIG_ESP_INT_WDT=n
|
||||||
CONFIG_ESP_INT_WDT_TIMEOUT_MS=1000
|
CONFIG_ESP_INT_WDT_TIMEOUT_MS=1000
|
||||||
CONFIG_ESP_INT_WDT_CHECK_CPU1=y
|
CONFIG_ESP_INT_WDT_CHECK_CPU1=y
|
||||||
CONFIG_ESP_TASK_WDT=y
|
CONFIG_ESP_TASK_WDT=n
|
||||||
# CONFIG_ESP_TASK_WDT_PANIC is not set
|
# CONFIG_ESP_TASK_WDT_PANIC is not set
|
||||||
CONFIG_ESP_TASK_WDT_TIMEOUT_S=5
|
CONFIG_ESP_TASK_WDT_TIMEOUT_S=5
|
||||||
CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
|
CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
|
||||||
@ -555,7 +555,7 @@ CONFIG_FREERTOS_TICK_SUPPORT_SYSTIMER=y
|
|||||||
CONFIG_FREERTOS_CORETIMER_SYSTIMER_LVL1=y
|
CONFIG_FREERTOS_CORETIMER_SYSTIMER_LVL1=y
|
||||||
# CONFIG_FREERTOS_CORETIMER_SYSTIMER_LVL3 is not set
|
# CONFIG_FREERTOS_CORETIMER_SYSTIMER_LVL3 is not set
|
||||||
CONFIG_FREERTOS_SYSTICK_USES_SYSTIMER=y
|
CONFIG_FREERTOS_SYSTICK_USES_SYSTIMER=y
|
||||||
CONFIG_FREERTOS_HZ=500
|
CONFIG_FREERTOS_HZ=1000
|
||||||
CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION=y
|
CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION=y
|
||||||
# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_NONE is not set
|
# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_NONE is not set
|
||||||
# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_PTRVAL is not set
|
# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_PTRVAL is not set
|
||||||
@ -1087,10 +1087,10 @@ CONFIG_CONSOLE_UART_DEFAULT=y
|
|||||||
CONFIG_CONSOLE_UART=y
|
CONFIG_CONSOLE_UART=y
|
||||||
CONFIG_CONSOLE_UART_NUM=0
|
CONFIG_CONSOLE_UART_NUM=0
|
||||||
CONFIG_CONSOLE_UART_BAUDRATE=115200
|
CONFIG_CONSOLE_UART_BAUDRATE=115200
|
||||||
CONFIG_INT_WDT=y
|
CONFIG_INT_WDT=n
|
||||||
CONFIG_INT_WDT_TIMEOUT_MS=1000
|
CONFIG_INT_WDT_TIMEOUT_MS=1000
|
||||||
CONFIG_INT_WDT_CHECK_CPU1=y
|
CONFIG_INT_WDT_CHECK_CPU1=y
|
||||||
CONFIG_TASK_WDT=y
|
CONFIG_TASK_WDT=n
|
||||||
# CONFIG_TASK_WDT_PANIC is not set
|
# CONFIG_TASK_WDT_PANIC is not set
|
||||||
CONFIG_TASK_WDT_TIMEOUT_S=5
|
CONFIG_TASK_WDT_TIMEOUT_S=5
|
||||||
CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
|
CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
|
||||||
|
Loading…
Reference in New Issue
Block a user