mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
remove AP_PeriodicProcess library, deprecated under AP_HAL
This commit is contained in:
parent
5b9738bba1
commit
2b904703d8
@ -1,9 +0,0 @@
|
||||
|
||||
#ifndef __AP_PERIODIC_PROCESS_H__
|
||||
#define __AP_PERIODIC_PROCESS_H__
|
||||
|
||||
#include "PeriodicProcess.h"
|
||||
#include "AP_PeriodicProcessStub.h"
|
||||
#include "AP_TimerProcess.h"
|
||||
|
||||
#endif // __AP_PERIODIC_PROCESS_H__
|
@ -1,22 +0,0 @@
|
||||
|
||||
#include "AP_PeriodicProcessStub.h"
|
||||
AP_PeriodicProcessStub::AP_PeriodicProcessStub(uint8_t period) {
|
||||
}
|
||||
void AP_PeriodicProcessStub::init( Arduino_Mega_ISR_Registry * isr_reg ){
|
||||
}
|
||||
void AP_PeriodicProcessStub::register_process(ap_procedure proc) {
|
||||
}
|
||||
void AP_PeriodicProcessStub::set_failsafe(ap_procedure proc) {
|
||||
}
|
||||
bool AP_PeriodicProcessStub::queue_process(ap_procedure proc) {
|
||||
return true;
|
||||
}
|
||||
void AP_PeriodicProcessStub::suspend_timer(void) {
|
||||
}
|
||||
void AP_PeriodicProcessStub::resume_timer(void) {
|
||||
}
|
||||
bool AP_PeriodicProcessStub::running(void) {
|
||||
return false;
|
||||
}
|
||||
void AP_PeriodicProcessStub::run(void) {
|
||||
}
|
@ -1,29 +0,0 @@
|
||||
|
||||
#ifndef __AP_PERIODIC_PROCESS_STUB_H__
|
||||
#define __AP_PERIODIC_PROCESS_STUB_H__
|
||||
|
||||
#include "PeriodicProcess.h"
|
||||
#include "../Arduino_Mega_ISR_Registry/Arduino_Mega_ISR_Registry.h"
|
||||
|
||||
|
||||
class AP_PeriodicProcessStub : public AP_PeriodicProcess
|
||||
{
|
||||
public:
|
||||
AP_PeriodicProcessStub(uint8_t period = 0);
|
||||
void init( Arduino_Mega_ISR_Registry * isr_reg );
|
||||
void register_process(ap_procedure proc);
|
||||
void set_failsafe(ap_procedure proc);
|
||||
bool queue_process(ap_procedure proc); // queue process to run as soon as possible after any currently running ap_processes complete. returns true if it ran immediately
|
||||
void suspend_timer(void);
|
||||
void resume_timer(void);
|
||||
bool running();
|
||||
static void run(void);
|
||||
protected:
|
||||
static uint8_t _period;
|
||||
static void (*_proc)(void);
|
||||
static void (*_failsafe)(void);
|
||||
static void (*_queued_proc)(void);
|
||||
static bool _suspended;
|
||||
};
|
||||
|
||||
#endif
|
@ -1,162 +0,0 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include "AP_TimerProcess.h"
|
||||
|
||||
extern "C" {
|
||||
#include <inttypes.h>
|
||||
#include <stdint.h>
|
||||
#include <avr/interrupt.h>
|
||||
}
|
||||
#if defined(ARDUINO) && ARDUINO >= 100
|
||||
#include "Arduino.h"
|
||||
#else
|
||||
#include "WConstants.h"
|
||||
#endif
|
||||
|
||||
uint8_t AP_TimerProcess::_period;
|
||||
ap_procedure AP_TimerProcess::_proc[AP_TIMERPROCESS_MAX_PROCS];
|
||||
ap_procedure AP_TimerProcess::_failsafe;
|
||||
ap_procedure AP_TimerProcess::_queued_proc = NULL;
|
||||
bool AP_TimerProcess::_in_timer_call;
|
||||
uint8_t AP_TimerProcess::_pidx = 0;
|
||||
bool AP_TimerProcess::_suspended;
|
||||
|
||||
AP_TimerProcess::AP_TimerProcess(uint8_t period)
|
||||
{
|
||||
_period = period;
|
||||
}
|
||||
|
||||
void AP_TimerProcess::init( Arduino_Mega_ISR_Registry * isr_reg )
|
||||
{
|
||||
// Enable Timer2 Overflow interrupt to trigger process.
|
||||
TIMSK2 = 0; // Disable interrupts
|
||||
TCCR2A = 0; // normal counting mode
|
||||
TCCR2B = _BV(CS21) | _BV(CS22); // Set prescaler of clk/256
|
||||
TCNT2 = 0; // Set count to zero, so it goes off right away.
|
||||
TIFR2 = _BV(TOV2); // clear pending interrupts;
|
||||
TIMSK2 = _BV(TOIE2); // enable the overflow interrupt
|
||||
|
||||
_failsafe = NULL;
|
||||
_suspended = false;
|
||||
_in_timer_call = false;
|
||||
|
||||
for (uint8_t i = 0; i < AP_TIMERPROCESS_MAX_PROCS; i++)
|
||||
_proc[i] = NULL;
|
||||
|
||||
isr_reg->register_signal( ISR_REGISTRY_TIMER2_OVF, AP_TimerProcess::run);
|
||||
}
|
||||
|
||||
/*
|
||||
* register a process to be called at the timer interrupt rate
|
||||
*/
|
||||
void AP_TimerProcess::register_process(ap_procedure proc)
|
||||
{
|
||||
// see if its already registered (due to double initialisation
|
||||
// of a driver)
|
||||
for (uint8_t i=0; i<_pidx; i++) {
|
||||
if (_proc[i] == proc) return;
|
||||
}
|
||||
uint8_t oldSREG = SREG;
|
||||
cli();
|
||||
if (_pidx < AP_TIMERPROCESS_MAX_PROCS)
|
||||
_proc[_pidx++] = proc;
|
||||
SREG = oldSREG;
|
||||
}
|
||||
|
||||
void AP_TimerProcess::set_failsafe(ap_procedure proc)
|
||||
{
|
||||
_failsafe = proc;
|
||||
}
|
||||
|
||||
/*
|
||||
* queue a process to be run as soon as any currently running ap_processes complete
|
||||
*/
|
||||
bool AP_TimerProcess::queue_process(ap_procedure proc)
|
||||
{
|
||||
// check if we are running any ap_processes
|
||||
if( _in_timer_call || _suspended ) {
|
||||
// queue the process to run after current processes finish
|
||||
_queued_proc = proc;
|
||||
return false;
|
||||
}else{
|
||||
// run process immediately
|
||||
_suspended = true;
|
||||
proc(micros());
|
||||
_suspended = false;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
void AP_TimerProcess::suspend_timer(void)
|
||||
{
|
||||
_suspended = true;
|
||||
}
|
||||
|
||||
void AP_TimerProcess::resume_timer(void)
|
||||
{
|
||||
_suspended = false;
|
||||
}
|
||||
|
||||
bool AP_TimerProcess::running(void) {
|
||||
return !_suspended;
|
||||
}
|
||||
|
||||
void AP_TimerProcess::run(void)
|
||||
{
|
||||
// we enable the interrupt again immediately and also enable
|
||||
// interrupts. This allows other time critical interrupts to
|
||||
// run (such as the serial receive interrupt). We catch the
|
||||
// timer calls taking too long using _in_timer_call.
|
||||
// This approach also gives us a nice uniform spacing between
|
||||
// timer calls
|
||||
TCNT2 = _period;
|
||||
sei();
|
||||
|
||||
uint32_t tnow = micros();
|
||||
|
||||
if (_in_timer_call) {
|
||||
// the timer calls took longer than the period of the
|
||||
// timer. This is bad, and may indicate a serious
|
||||
// driver failure. We can't just call the drivers
|
||||
// again, as we could run out of stack. So we only
|
||||
// call the _failsafe call. It's job is to detect if
|
||||
// the drivers or the main loop are indeed dead and to
|
||||
// activate whatever failsafe it thinks may help if
|
||||
// need be. We assume the failsafe code can't
|
||||
// block. If it does then we will recurse and die when
|
||||
// we run out of stack
|
||||
if (_failsafe != NULL) {
|
||||
_failsafe(tnow);
|
||||
}
|
||||
return;
|
||||
}
|
||||
_in_timer_call = true;
|
||||
|
||||
if (!_suspended) {
|
||||
// now call the timer based drivers
|
||||
for (int i = 0; i < _pidx; i++) {
|
||||
if (_proc[i] != NULL) {
|
||||
_proc[i](tnow);
|
||||
}
|
||||
}
|
||||
|
||||
// run any queued processes
|
||||
uint8_t oldSREG = SREG;
|
||||
cli();
|
||||
ap_procedure qp = _queued_proc;
|
||||
_queued_proc = NULL;
|
||||
SREG = oldSREG;
|
||||
if( qp != NULL ) {
|
||||
_suspended = true;
|
||||
qp(tnow);
|
||||
_suspended = false;
|
||||
}
|
||||
}
|
||||
|
||||
// and the failsafe, if one is setup
|
||||
if (_failsafe != NULL) {
|
||||
_failsafe(tnow);
|
||||
}
|
||||
|
||||
_in_timer_call = false;
|
||||
}
|
@ -1,35 +0,0 @@
|
||||
|
||||
#ifndef __AP_TIMERPROCESS_H__
|
||||
#define __AP_TIMERPROCESS_H__
|
||||
|
||||
#include "PeriodicProcess.h"
|
||||
#include "../Arduino_Mega_ISR_Registry/Arduino_Mega_ISR_Registry.h"
|
||||
|
||||
// default to 1kHz timer interrupt
|
||||
#define TIMERPROCESS_PER_DEFAULT (256-62) // 1kHz
|
||||
|
||||
#define AP_TIMERPROCESS_MAX_PROCS 5
|
||||
|
||||
class AP_TimerProcess : public AP_PeriodicProcess
|
||||
{
|
||||
public:
|
||||
AP_TimerProcess(uint8_t period = TIMERPROCESS_PER_DEFAULT);
|
||||
void init( Arduino_Mega_ISR_Registry * isr_reg );
|
||||
void register_process(ap_procedure proc);
|
||||
bool queue_process(ap_procedure proc); // queue process to run as soon as possible after any currently running ap_processes complete. returns true if it ran immediately
|
||||
void set_failsafe(ap_procedure proc);
|
||||
void suspend_timer(void);
|
||||
void resume_timer(void);
|
||||
bool running();
|
||||
static void run(void);
|
||||
protected:
|
||||
static uint8_t _period;
|
||||
static ap_procedure _proc[AP_TIMERPROCESS_MAX_PROCS];
|
||||
static ap_procedure _failsafe;
|
||||
static ap_procedure _queued_proc;
|
||||
static uint8_t _pidx;
|
||||
static bool _in_timer_call;
|
||||
static bool _suspended;
|
||||
};
|
||||
|
||||
#endif // __AP_TIMERPROCESS_H__
|
@ -1,23 +0,0 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#ifndef __PERIODICPROCESS_H__
|
||||
#define __PERIODICPROCESS_H__
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
// the callback type for periodic processes. They are passed the time
|
||||
// in microseconds since boot
|
||||
typedef void (*ap_procedure)(uint32_t );
|
||||
|
||||
class AP_PeriodicProcess
|
||||
{
|
||||
public:
|
||||
virtual void register_process(ap_procedure proc) = 0;
|
||||
virtual void set_failsafe(ap_procedure proc) = 0;
|
||||
virtual bool queue_process(ap_procedure proc) = 0; // queue process to run as soon as possible after any currently running ap_processes complete. returns true if it ran immediately
|
||||
virtual void suspend_timer(void) = 0;
|
||||
virtual void resume_timer(void) = 0;
|
||||
virtual bool running() = 0;
|
||||
};
|
||||
|
||||
#endif // __PERIODICPROCESS_H__
|
@ -1,49 +0,0 @@
|
||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
//
|
||||
// Simple test for the AP_TimerProcess library
|
||||
//
|
||||
|
||||
#include <FastSerial.h>
|
||||
#include <Arduino_Mega_ISR_Registry.h>
|
||||
#include <AP_PeriodicProcess.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_Common.h>
|
||||
|
||||
FastSerialPort0(Serial);
|
||||
FastSerialPort1(Serial1);
|
||||
|
||||
Arduino_Mega_ISR_Registry isr_registry;
|
||||
AP_TimerProcess scheduler;
|
||||
|
||||
uint32_t counter;
|
||||
|
||||
void ping(uint32_t now)
|
||||
{
|
||||
counter++;
|
||||
}
|
||||
|
||||
void setup(void)
|
||||
{
|
||||
Serial.begin(115200);
|
||||
Serial.println("AP_TimerProcess Test ver 0.1");
|
||||
|
||||
isr_registry.init();
|
||||
scheduler.init(&isr_registry);
|
||||
|
||||
// register our ping function
|
||||
scheduler.register_process(ping);
|
||||
}
|
||||
|
||||
void loop(void)
|
||||
{
|
||||
static uint32_t secs = 0;
|
||||
|
||||
// check if 1second has passed
|
||||
if( counter >= 1000 ) {
|
||||
counter -= 1000;
|
||||
secs++;
|
||||
Serial.print("Seconds: ");
|
||||
Serial.println(secs);
|
||||
}
|
||||
}
|
@ -1,4 +0,0 @@
|
||||
include ../../../AP_Common/Arduino.mk
|
||||
|
||||
sitl:
|
||||
make -f ../../../../libraries/Desktop/Desktop.mk
|
Loading…
Reference in New Issue
Block a user