ardupilot/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp

107 lines
2.2 KiB
C++
Raw Normal View History

2014-11-27 21:59:47 -04:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
//
// Simple test for the AP_Scheduler interface
//
#include <AP_HAL/AP_HAL.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Scheduler/AP_Scheduler.h>
2014-11-27 21:59:47 -04:00
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
2014-11-27 21:59:47 -04:00
2015-06-01 04:42:32 -03:00
class SchedTest {
public:
void setup();
void loop();
2014-11-27 21:59:47 -04:00
2015-06-01 04:42:32 -03:00
private:
2014-11-27 21:59:47 -04:00
2015-06-01 04:42:32 -03:00
AP_InertialSensor ins;
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, _interval_ticks, _max_time_micros) SCHED_TASK_CLASS(SchedTest, &schedtest, func, _interval_ticks, _max_time_micros)
2014-11-27 21:59:47 -04:00
/*
scheduler table - all regular tasks are listed here, along with how
often they should be called (in 20ms units) and the maximum time
they are expected to take (in microseconds)
*/
const AP_Scheduler::Task SchedTest::scheduler_tasks[] = {
SCHED_TASK(ins_update, 50, 1000),
SCHED_TASK(one_hz_print, 1, 1000),
SCHED_TASK(five_second_call, 0.2, 1800),
2014-11-27 21:59:47 -04:00
};
2015-06-01 04:42:32 -03:00
void SchedTest::setup(void)
2014-11-27 21:59:47 -04:00
{
ins.init(scheduler.get_loop_rate_hz());
2014-11-27 21:59:47 -04:00
// initialise the scheduler
2015-07-20 16:53:47 -03:00
scheduler.init(&scheduler_tasks[0], ARRAY_SIZE(scheduler_tasks));
2014-11-27 21:59:47 -04:00
}
2015-06-01 04:42:32 -03:00
void SchedTest::loop(void)
2014-11-27 21:59:47 -04:00
{
// wait for an INS sample
ins.wait_for_sample();
// tell the scheduler one tick has passed
scheduler.tick();
// run all tasks that fit in 20ms
scheduler.run(20000);
}
/*
update inertial sensor, reading data
*/
2015-06-01 04:42:32 -03:00
void SchedTest::ins_update(void)
2014-11-27 21:59:47 -04:00
{
ins_counter++;
ins.update();
}
/*
print something once a second
*/
2015-06-01 04:42:32 -03:00
void SchedTest::one_hz_print(void)
2014-11-27 21:59:47 -04:00
{
hal.console->printf("one_hz: t=%lu\n", (unsigned long)AP_HAL::millis());
2014-11-27 21:59:47 -04:00
}
/*
print something every 5 seconds
*/
2015-06-01 04:42:32 -03:00
void SchedTest::five_second_call(void)
2014-11-27 21:59:47 -04:00
{
hal.console->printf("five_seconds: t=%lu ins_counter=%u\n", (unsigned long)AP_HAL::millis(), ins_counter);
2014-11-27 21:59:47 -04:00
}
2015-06-01 04:42:32 -03:00
/*
compatibility with old pde style build
*/
void setup(void);
void loop(void);
void setup(void)
{
schedtest.setup();
}
void loop(void)
{
schedtest.loop();
}
2014-11-27 21:59:47 -04:00
AP_HAL_MAIN();