2018-01-05 02:19:51 -04:00
|
|
|
/*
|
|
|
|
* This file is free software: you can redistribute it and/or modify it
|
|
|
|
* under the terms of the GNU General Public License as published by the
|
|
|
|
* Free Software Foundation, either version 3 of the License, or
|
|
|
|
* (at your option) any later version.
|
|
|
|
*
|
|
|
|
* This file is distributed in the hope that it will be useful, but
|
|
|
|
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
|
|
* See the GNU General Public License for more details.
|
|
|
|
*
|
|
|
|
* You should have received a copy of the GNU General Public License along
|
|
|
|
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
2019-10-20 10:31:12 -03:00
|
|
|
*
|
2018-01-05 02:19:51 -04:00
|
|
|
* Code by Andrew Tridgell and Siddharth Bharat Purohit
|
|
|
|
*/
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
|
|
|
#include "AP_HAL_ChibiOS_Namespace.h"
|
|
|
|
|
|
|
|
#define CHIBIOS_SCHEDULER_MAX_TIMER_PROCS 8
|
|
|
|
|
2019-05-09 08:15:58 -03:00
|
|
|
#define APM_MONITOR_PRIORITY 183
|
2018-01-05 02:19:51 -04:00
|
|
|
#define APM_MAIN_PRIORITY 180
|
2018-08-05 22:40:38 -03:00
|
|
|
#define APM_TIMER_PRIORITY 181
|
2020-12-05 15:16:27 -04:00
|
|
|
#define APM_RCOUT_PRIORITY 181
|
2023-02-23 08:35:34 -04:00
|
|
|
#define APM_LED_PRIORITY 60
|
2018-01-05 02:19:51 -04:00
|
|
|
#define APM_UART_PRIORITY 60
|
2023-12-24 23:25:19 -04:00
|
|
|
#define APM_NET_PRIORITY 60
|
2020-12-05 15:16:27 -04:00
|
|
|
#define APM_UART_UNBUFFERED_PRIORITY 181
|
2018-01-05 02:19:51 -04:00
|
|
|
#define APM_STORAGE_PRIORITY 59
|
|
|
|
#define APM_IO_PRIORITY 58
|
|
|
|
#define APM_STARTUP_PRIORITY 10
|
2018-09-27 20:17:27 -03:00
|
|
|
#define APM_SCRIPTING_PRIORITY LOWPRIO
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-04-02 23:25:42 -03:00
|
|
|
/*
|
|
|
|
boost priority handling
|
|
|
|
*/
|
|
|
|
#ifndef APM_MAIN_PRIORITY_BOOST
|
|
|
|
#define APM_MAIN_PRIORITY_BOOST 182
|
|
|
|
#endif
|
|
|
|
|
2023-08-24 02:47:42 -03:00
|
|
|
#ifndef APM_RCIN_PRIORITY
|
|
|
|
#define APM_RCIN_PRIORITY 177
|
|
|
|
#endif
|
|
|
|
|
2018-01-17 04:36:12 -04:00
|
|
|
#ifndef APM_SPI_PRIORITY
|
2018-04-02 04:39:10 -03:00
|
|
|
// SPI priority needs to be above main priority to ensure fast sampling of IMUs can keep up
|
|
|
|
// with the data rate
|
|
|
|
#define APM_SPI_PRIORITY 181
|
2018-01-17 04:36:12 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef APM_CAN_PRIORITY
|
2018-02-27 19:59:47 -04:00
|
|
|
#define APM_CAN_PRIORITY 178
|
2018-01-17 04:36:12 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef APM_I2C_PRIORITY
|
|
|
|
#define APM_I2C_PRIORITY 176
|
|
|
|
#endif
|
|
|
|
|
2018-08-29 10:14:45 -03:00
|
|
|
#ifndef TIMER_THD_WA_SIZE
|
2021-01-06 20:14:55 -04:00
|
|
|
#define TIMER_THD_WA_SIZE 1536
|
2018-08-29 10:14:45 -03:00
|
|
|
#endif
|
|
|
|
|
2020-12-05 15:16:27 -04:00
|
|
|
#ifndef RCOUT_THD_WA_SIZE
|
2021-02-17 13:56:14 -04:00
|
|
|
#define RCOUT_THD_WA_SIZE 512
|
2020-12-05 15:16:27 -04:00
|
|
|
#endif
|
|
|
|
|
2018-08-29 10:14:45 -03:00
|
|
|
#ifndef RCIN_THD_WA_SIZE
|
2020-12-05 15:16:27 -04:00
|
|
|
#define RCIN_THD_WA_SIZE 1024
|
2018-08-29 10:14:45 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef IO_THD_WA_SIZE
|
|
|
|
#define IO_THD_WA_SIZE 2048
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef STORAGE_THD_WA_SIZE
|
2021-02-17 13:56:14 -04:00
|
|
|
#define STORAGE_THD_WA_SIZE 1024
|
2018-08-29 10:14:45 -03:00
|
|
|
#endif
|
|
|
|
|
2019-05-09 08:15:58 -03:00
|
|
|
#ifndef MONITOR_THD_WA_SIZE
|
2022-04-04 04:10:20 -03:00
|
|
|
#define MONITOR_THD_WA_SIZE 1024
|
2019-05-09 08:15:58 -03:00
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
/* Scheduler implementation: */
|
2018-01-13 00:02:05 -04:00
|
|
|
class ChibiOS::Scheduler : public AP_HAL::Scheduler {
|
2018-01-05 02:19:51 -04:00
|
|
|
public:
|
2018-01-13 00:02:05 -04:00
|
|
|
Scheduler();
|
2018-01-05 02:19:51 -04:00
|
|
|
/* AP_HAL::Scheduler methods */
|
|
|
|
|
|
|
|
|
2018-11-07 06:58:46 -04:00
|
|
|
void init() override;
|
2018-05-04 05:30:25 -03:00
|
|
|
void delay(uint16_t ms) override;
|
|
|
|
void delay_microseconds(uint16_t us) override;
|
|
|
|
void delay_microseconds_boost(uint16_t us) override;
|
|
|
|
void boost_end(void) override;
|
|
|
|
void register_timer_process(AP_HAL::MemberProc) override;
|
|
|
|
void register_io_process(AP_HAL::MemberProc) override;
|
|
|
|
void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us) override;
|
|
|
|
void reboot(bool hold_in_bootloader) override;
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2019-05-09 08:15:58 -03:00
|
|
|
bool in_main_thread() const override { return get_main_thread() == chThdGetSelfX(); }
|
|
|
|
|
2020-12-23 07:26:59 -04:00
|
|
|
void set_system_initialized() override;
|
|
|
|
bool is_system_initialized() override { return _initialized; };
|
2018-01-05 02:19:51 -04:00
|
|
|
void hal_initialized() { _hal_initialized = true; }
|
|
|
|
|
2018-02-09 22:46:55 -04:00
|
|
|
bool check_called_boost(void);
|
2018-03-28 05:49:51 -03:00
|
|
|
|
2019-04-11 08:12:03 -03:00
|
|
|
/*
|
|
|
|
inform the scheduler that we are calling an operation from the
|
|
|
|
main thread that may take an extended amount of time. This can
|
|
|
|
be used to prevent watchdog reset during expected long delays
|
|
|
|
A value of zero cancels the previous expected delay
|
|
|
|
*/
|
2020-04-12 08:04:26 -03:00
|
|
|
void _expect_delay_ms(uint32_t ms);
|
2019-04-11 08:12:03 -03:00
|
|
|
void expect_delay_ms(uint32_t ms) override;
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2020-03-10 22:20:47 -03:00
|
|
|
/*
|
|
|
|
return true if we are in a period of expected delay. This can be
|
|
|
|
used to suppress error messages
|
|
|
|
*/
|
|
|
|
bool in_expected_delay(void) const override;
|
|
|
|
|
2018-03-28 05:49:51 -03:00
|
|
|
/*
|
|
|
|
disable interrupts and return a context that can be used to
|
|
|
|
restore the interrupt state. This can be used to protect
|
|
|
|
critical regions
|
|
|
|
*/
|
|
|
|
void *disable_interrupts_save(void) override;
|
|
|
|
|
|
|
|
/*
|
|
|
|
restore interrupt state from disable_interrupts_save()
|
|
|
|
*/
|
|
|
|
void restore_interrupts(void *) override;
|
2018-07-06 20:59:10 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
create a new thread
|
|
|
|
*/
|
|
|
|
bool thread_create(AP_HAL::MemberProc, const char *name, uint32_t stack_size, priority_base base, int8_t priority) override;
|
2018-02-27 19:59:47 -04:00
|
|
|
|
2019-05-09 08:15:58 -03:00
|
|
|
// pat the watchdog
|
|
|
|
void watchdog_pat(void);
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
private:
|
|
|
|
bool _initialized;
|
|
|
|
volatile bool _hal_initialized;
|
|
|
|
AP_HAL::Proc _failsafe;
|
2018-02-09 22:46:55 -04:00
|
|
|
bool _called_boost;
|
2018-05-04 05:30:25 -03:00
|
|
|
bool _priority_boosted;
|
2019-04-11 08:12:03 -03:00
|
|
|
uint32_t expect_delay_start;
|
|
|
|
uint32_t expect_delay_length;
|
2019-05-11 05:20:53 -03:00
|
|
|
uint32_t expect_delay_nesting;
|
2020-04-12 08:04:26 -03:00
|
|
|
HAL_Semaphore expect_delay_sem;
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
AP_HAL::MemberProc _timer_proc[CHIBIOS_SCHEDULER_MAX_TIMER_PROCS];
|
|
|
|
uint8_t _num_timer_procs;
|
|
|
|
volatile bool _in_timer_proc;
|
|
|
|
|
|
|
|
AP_HAL::MemberProc _io_proc[CHIBIOS_SCHEDULER_MAX_TIMER_PROCS];
|
|
|
|
uint8_t _num_io_procs;
|
|
|
|
volatile bool _in_io_proc;
|
2019-05-09 08:15:58 -03:00
|
|
|
uint32_t last_watchdog_pat_ms;
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
thread_t* _timer_thread_ctx;
|
2020-12-05 15:16:27 -04:00
|
|
|
thread_t* _rcout_thread_ctx;
|
2018-01-18 15:12:38 -04:00
|
|
|
thread_t* _rcin_thread_ctx;
|
2018-01-05 02:19:51 -04:00
|
|
|
thread_t* _io_thread_ctx;
|
|
|
|
thread_t* _storage_thread_ctx;
|
2019-05-09 08:15:58 -03:00
|
|
|
thread_t* _monitor_thread_ctx;
|
2018-02-27 19:59:47 -04:00
|
|
|
|
2018-06-25 01:10:06 -03:00
|
|
|
#if CH_CFG_USE_SEMAPHORES == TRUE
|
2018-05-21 20:08:35 -03:00
|
|
|
binary_semaphore_t _timer_semaphore;
|
|
|
|
binary_semaphore_t _io_semaphore;
|
2018-06-25 01:10:06 -03:00
|
|
|
#endif
|
2021-03-17 23:10:29 -03:00
|
|
|
|
|
|
|
// calculates an integer to be used as the priority for a newly-created thread
|
|
|
|
uint8_t calculate_thread_priority(priority_base base, int8_t priority) const;
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
static void _timer_thread(void *arg);
|
2020-12-05 15:16:27 -04:00
|
|
|
static void _rcout_thread(void *arg);
|
2018-01-18 15:12:38 -04:00
|
|
|
static void _rcin_thread(void *arg);
|
2018-01-05 02:19:51 -04:00
|
|
|
static void _io_thread(void *arg);
|
|
|
|
static void _storage_thread(void *arg);
|
|
|
|
static void _uart_thread(void *arg);
|
2019-05-09 08:15:58 -03:00
|
|
|
static void _monitor_thread(void *arg);
|
2018-02-27 19:59:47 -04:00
|
|
|
|
2018-05-13 19:47:14 -03:00
|
|
|
void _run_timers();
|
2018-01-05 02:19:51 -04:00
|
|
|
void _run_io(void);
|
2019-10-20 10:31:12 -03:00
|
|
|
static void thread_create_trampoline(void *ctx);
|
2020-11-14 17:23:45 -04:00
|
|
|
|
|
|
|
#if defined STM32H7
|
|
|
|
void check_low_memory_is_zero();
|
|
|
|
#endif
|
2020-11-29 15:53:49 -04:00
|
|
|
|
|
|
|
// check for free stack space
|
|
|
|
void check_stack_free(void);
|
2023-05-11 04:06:28 -03:00
|
|
|
|
|
|
|
#if defined(HAL_GPIO_PIN_EXT_WDOG)
|
|
|
|
// external watchdog GPIO support
|
|
|
|
void ext_watchdog_pat(uint32_t now_ms);
|
|
|
|
uint32_t last_ext_watchdog_ms;
|
|
|
|
#endif
|
2023-06-15 20:54:23 -03:00
|
|
|
|
|
|
|
static void try_force_mutex(void);
|
2018-01-05 02:19:51 -04:00
|
|
|
};
|
|
|
|
#endif
|