APM:Libraries
|
#include <AP_HAL/AP_HAL.h>
#include "AP_HAL_F4Light_Namespace.h"
#include "handler.h"
#include "Config.h"
#include "Semaphores.h"
#include "GPIO.h"
#include <delay.h>
#include <systick.h>
#include <boards.h>
#include <timer.h>
Go to the source code of this file.
Classes | |
struct | task_t |
struct | REVO_IO |
class | F4Light::Scheduler |
struct | F4Light::Scheduler::IO_COMPLETION |
Macros | |
#define | F4Light_SCHEDULER_MAX_IO_PROCS 10 |
#define | MAIN_PRIORITY 100 |
#define | DRIVER_PRIORITY 98 |
#define | IO_PRIORITY 115 |
#define | SHED_FREQ 10000 |
#define | TIMER_PERIOD 100 |
#define | MAIN_STACK_SIZE 4096U+1024U |
#define | IO_STACK_SIZE 4096U |
#define | DEFAULT_STACK_SIZE 1024U |
#define | SMALL_TASK_STACK 1024U |
#define | STACK_MAX 65536U |
#define | EnterCriticalSection __set_BASEPRI(SVC_INT_PRIORITY << (8 - __NVIC_PRIO_BITS)) |
#define | LeaveCriticalSection __set_BASEPRI(0) |
#define | RAMEND ((size_t)&_estack) |
#define | MAX_IO_COMPLETION 8 |
#define | await(cond) while(!(cond)) yield() |
Typedefs | |
typedef struct REVO_IO | Revo_IO |
Enumerations | |
enum | Revo_IO_Flags { IO_PERIODIC = 0, IO_ONCE = 1 } |
Functions | |
void | revo_call_handler (Handler hh, uint32_t arg) |
void | PendSV_Handler () |
void | SVC_Handler () |
void | getNextTask () |
void | switchContext () |
void | __do_context_switch () |
void | hal_try_kill_task_or_reboot (uint8_t n) |
void | hal_go_next_task () |
void | hal_stop_multitask () |
bool | hal_is_armed () |
void | hal_yield (uint16_t ttw) |
void | hal_delay (uint16_t t) |
void | hal_delay_microseconds (uint16_t t) |
uint32_t | hal_micros () |
void | hal_isr_time (uint32_t t) |
void | hal_set_task_active (void *handle) |
void | hal_context_switch_isr () |
void * | hal_register_task (voidFuncPtr task, uint32_t stack) |
void | hal_set_task_priority (void *handle, uint8_t prio) |
void | enqueue_flash_erase (uint32_t from, uint32_t to) |
Variables | |
unsigned | _estack |
uint32_t | us_ticks |
void * | _sdata |
void * | _edata |
void * | _sccm |
void * | _eccm |
voidFuncPtr | boardEmergencyHandler |
task_t * | s_running |
task_t * | next_task |
caddr_t | stack_bottom |
#define await | ( | cond | ) | while(!(cond)) yield() |
Definition at line 498 of file Scheduler.h.
#define DEFAULT_STACK_SIZE 1024U |
Definition at line 34 of file Scheduler.h.
#define DRIVER_PRIORITY 98 |
Definition at line 25 of file Scheduler.h.
Referenced by F4Light::Scheduler::_register_timer_task(), and F4Light::AnalogIn::init().
#define EnterCriticalSection __set_BASEPRI(SVC_INT_PRIORITY << (8 - __NVIC_PRIO_BITS)) |
Definition at line 39 of file Scheduler.h.
Referenced by F4Light::AnalogSource::_read_average(), F4Light::SPIDevice::do_transfer(), F4Light::I2CDevice::i2c_read(), F4Light::I2CDevice::i2c_write(), F4Light::AnalogSource::new_sample(), and F4Light::SPIDevice::wait_for().
#define F4Light_SCHEDULER_MAX_IO_PROCS 10 |
Definition at line 21 of file Scheduler.h.
Referenced by F4Light::Scheduler::_register_io_process().
#define IO_PRIORITY 115 |
Definition at line 26 of file Scheduler.h.
Referenced by F4Light::Scheduler::_register_io_process(), F4Light::Scheduler::start_stats_task(), and F4Light::Scheduler::SVC_Handler().
#define IO_STACK_SIZE 4096U |
Definition at line 33 of file Scheduler.h.
Referenced by F4Light::Scheduler::_register_io_process().
#define LeaveCriticalSection __set_BASEPRI(0) |
Definition at line 40 of file Scheduler.h.
Referenced by F4Light::AnalogSource::_read_average(), F4Light::SPIDevice::do_transfer(), F4Light::I2CDevice::i2c_read(), F4Light::I2CDevice::i2c_write(), F4Light::AnalogSource::new_sample(), and F4Light::SPIDevice::wait_for().
#define MAIN_PRIORITY 100 |
Definition at line 24 of file Scheduler.h.
Referenced by F4Light::Scheduler::fill_task(), F4Light::Storage::init(), and F4Light::Scheduler::Scheduler().
#define MAIN_STACK_SIZE 4096U+1024U |
Definition at line 32 of file Scheduler.h.
Referenced by F4Light::Scheduler::Scheduler().
#define MAX_IO_COMPLETION 8 |
Definition at line 407 of file Scheduler.h.
Referenced by F4Light::Scheduler::register_io_completion().
#define RAMEND ((size_t)&_estack) |
Definition at line 135 of file Scheduler.h.
Referenced by F4Light::Scheduler::_start_task().
#define SHED_FREQ 10000 |
Definition at line 28 of file Scheduler.h.
Referenced by F4Light::Scheduler::init().
#define SMALL_TASK_STACK 1024U |
Definition at line 35 of file Scheduler.h.
Referenced by F4Light::Scheduler::_register_timer_task().
#define STACK_MAX 65536U |
Definition at line 36 of file Scheduler.h.
#define TIMER_PERIOD 100 |
Definition at line 29 of file Scheduler.h.
Referenced by F4Light::Scheduler::get_next_task().
enum Revo_IO_Flags |
Enumerator | |
---|---|
IO_PERIODIC | |
IO_ONCE |
Definition at line 157 of file Scheduler.h.
void __do_context_switch | ( | ) |
void enqueue_flash_erase | ( | uint32_t | from, |
uint32_t | to | ||
) |
void getNextTask | ( | ) |
void hal_delay | ( | uint16_t | t | ) |
void hal_delay_microseconds | ( | uint16_t | t | ) |
void hal_go_next_task | ( | ) |
bool hal_is_armed | ( | ) |
void hal_isr_time | ( | uint32_t | t | ) |
Definition at line 1435 of file Scheduler.cpp.
uint32_t hal_micros | ( | ) |
void hal_stop_multitask | ( | ) |
void hal_try_kill_task_or_reboot | ( | uint8_t | n | ) |
void hal_yield | ( | uint16_t | ttw | ) |
void PendSV_Handler | ( | ) |
void revo_call_handler | ( | Handler | hh, |
uint32_t | arg | ||
) |
Definition at line 1420 of file Scheduler.cpp.
Referenced by F4Light::Scheduler::_ioc_timer_event(), F4Light::Scheduler::_run_io(), F4Light::Scheduler::arming_state_changed(), and F4Light::Scheduler::do_task().
void SVC_Handler | ( | ) |
Definition at line 1293 of file Scheduler.cpp.
Referenced by F4Light::Scheduler::plan_context_switch().
void switchContext | ( | ) |
void* _eccm |
void* _edata |
Referenced by F4Light::Scheduler::_print_stats().
unsigned _estack |
void* _sccm |
Referenced by F4Light::Scheduler::_print_stats(), and setupCCM().
void* _sdata |
Referenced by F4Light::Scheduler::_print_stats().
voidFuncPtr boardEmergencyHandler |
Referenced by F4Light::Scheduler::setEmergencyHandler().
task_t* next_task |
task_t* s_running |
Referenced by F4Light::Scheduler::_in_main_thread(), F4Light::Scheduler::_ioc_timer_event(), F4Light::Scheduler::_switch_task(), F4Light::Scheduler::_tail_timer_event(), F4Light::Scheduler::_timer_isr_event(), F4Light::Scheduler::_try_kill_task_or_reboot(), F4Light::Scheduler::get_current_task(), F4Light::Scheduler::get_current_task_isr(), F4Light::Scheduler::get_next_task(), hal_isr_time(), F4Light::Scheduler::Scheduler(), F4Light::Scheduler::SVC_Handler(), F4Light::Scheduler::task_pause(), F4Light::Scheduler::task_resume(), F4Light::Scheduler::task_stack(), and F4Light::Scheduler::yield().
caddr_t stack_bottom |
Definition at line 74 of file syscalls.c.
Referenced by _sbrk_ccm(), and F4Light::Scheduler::_start_task().
uint32_t us_ticks |
Definition at line 10 of file stopwatch.c.
Referenced by F4Light::Scheduler::_delay_us_ny(), F4Light::Scheduler::_print_stats(), Soft_I2C::bus_reset(), i2c_bus_reset(), stopwatch_delay_us(), and stopwatch_init().