Browse Source

AP_Scheduler: fixed example sketch

mission-4.1.18
Andrew Tridgell 10 years ago
parent
commit
b2a5de8a63
  1. 57
      libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp
  2. 1
      libraries/AP_Scheduler/examples/Scheduler_test/make.inc

57
libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp

@ -42,28 +42,41 @@
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
// INS declaration class SchedTest {
static AP_InertialSensor ins; public:
void setup();
void loop();
// loop scheduler object private:
static AP_Scheduler scheduler;
// counter for ins_update() AP_InertialSensor ins;
static uint32_t ins_counter; AP_Scheduler scheduler;
uint32_t ins_counter;
static const AP_Scheduler::Task scheduler_tasks[];
void ins_update(void);
void one_hz_print(void);
void five_second_call(void);
};
static SchedTest schedtest;
#define SCHED_TASK(func) FUNCTOR_BIND_VOID(&schedtest, &SchedTest::func, void)
/* /*
scheduler table - all regular tasks are listed here, along with how scheduler table - all regular tasks are listed here, along with how
often they should be called (in 20ms units) and the maximum time often they should be called (in 20ms units) and the maximum time
they are expected to take (in microseconds) they are expected to take (in microseconds)
*/ */
static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = { const AP_Scheduler::Task SchedTest::scheduler_tasks[] PROGMEM = {
{ ins_update, 1, 1000 }, { SCHED_TASK(ins_update), 1, 1000 },
{ one_hz_print, 50, 1000 }, { SCHED_TASK(one_hz_print), 50, 1000 },
{ five_second_call, 250, 1800 }, { SCHED_TASK(five_second_call), 250, 1800 },
}; };
void setup(void) void SchedTest::setup(void)
{ {
// we // we
ins.init(AP_InertialSensor::COLD_START, ins.init(AP_InertialSensor::COLD_START,
@ -73,7 +86,7 @@ void setup(void)
scheduler.init(&scheduler_tasks[0], sizeof(scheduler_tasks)/sizeof(scheduler_tasks[0])); scheduler.init(&scheduler_tasks[0], sizeof(scheduler_tasks)/sizeof(scheduler_tasks[0]));
} }
void loop(void) void SchedTest::loop(void)
{ {
// wait for an INS sample // wait for an INS sample
ins.wait_for_sample(); ins.wait_for_sample();
@ -88,7 +101,7 @@ void loop(void)
/* /*
update inertial sensor, reading data update inertial sensor, reading data
*/ */
static void ins_update(void) void SchedTest::ins_update(void)
{ {
ins_counter++; ins_counter++;
ins.update(); ins.update();
@ -97,7 +110,7 @@ static void ins_update(void)
/* /*
print something once a second print something once a second
*/ */
static void one_hz_print(void) void SchedTest::one_hz_print(void)
{ {
hal.console->printf("one_hz: t=%lu\n", hal.scheduler->millis()); hal.console->printf("one_hz: t=%lu\n", hal.scheduler->millis());
} }
@ -105,9 +118,23 @@ static void one_hz_print(void)
/* /*
print something every 5 seconds print something every 5 seconds
*/ */
static void five_second_call(void) void SchedTest::five_second_call(void)
{ {
hal.console->printf("five_seconds: t=%lu ins_counter=%u\n", hal.scheduler->millis(), ins_counter); hal.console->printf("five_seconds: t=%lu ins_counter=%u\n", hal.scheduler->millis(), ins_counter);
} }
/*
compatibility with old pde style build
*/
void setup(void);
void loop(void);
void setup(void)
{
schedtest.setup();
}
void loop(void)
{
schedtest.loop();
}
AP_HAL_MAIN(); AP_HAL_MAIN();

1
libraries/AP_Scheduler/examples/Scheduler_test/make.inc

@ -31,3 +31,4 @@ LIBRARIES += Filter
LIBRARIES += GCS_MAVLink LIBRARIES += GCS_MAVLink
LIBRARIES += SITL LIBRARIES += SITL
LIBRARIES += StorageManager LIBRARIES += StorageManager
LIBRARIES += AP_OpticalFlow

Loading…
Cancel
Save