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

141 lines
2.9 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.h>
#include <AP_Common.h>
#include <AP_Progmem.h>
#include <AP_Math.h>
#include <AP_Param.h>
#include <AP_InertialSensor.h>
#include <AP_ADC.h>
#include <AP_ADC_AnalogSource.h>
#include <AP_Baro.h>
#include <AP_GPS.h>
#include <AP_AHRS.h>
#include <AP_Compass.h>
#include <AP_Declination.h>
#include <AP_Airspeed.h>
#include <AP_Baro.h>
#include <GCS_MAVLink.h>
#include <AP_Mission.h>
#include <StorageManager.h>
#include <AP_Terrain.h>
#include <Filter.h>
#include <SITL.h>
#include <AP_Buffer.h>
#include <AP_Notify.h>
#include <AP_Vehicle.h>
#include <DataFlash.h>
#include <AP_NavEKF.h>
#include <AP_Rally.h>
2015-01-28 04:12:55 -04:00
#include <AP_BattMonitor.h>
2014-11-27 21:59:47 -04:00
#include <AP_Scheduler.h>
2015-05-01 23:55:50 -03:00
#include <AP_RangeFinder.h>
2014-11-27 21:59:47 -04:00
#include <AP_HAL_AVR.h>
2015-05-04 03:17:26 -03:00
#include <AP_HAL_SITL.h>
2014-11-27 21:59:47 -04:00
#include <AP_HAL_Empty.h>
#include <AP_HAL_PX4.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
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) FUNCTOR_BIND_VOID(&schedtest, &SchedTest::func, void)
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)
*/
2015-06-01 04:42:32 -03:00
const AP_Scheduler::Task SchedTest::scheduler_tasks[] PROGMEM = {
{ SCHED_TASK(ins_update), 1, 1000 },
{ SCHED_TASK(one_hz_print), 50, 1000 },
{ SCHED_TASK(five_second_call), 250, 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
{
// we
ins.init(AP_InertialSensor::COLD_START,
AP_InertialSensor::RATE_50HZ);
// initialise the scheduler
2015-05-26 01:37:14 -03:00
scheduler.init(&scheduler_tasks[0], sizeof(scheduler_tasks)/sizeof(scheduler_tasks[0]));
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", hal.scheduler->millis());
}
/*
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", hal.scheduler->millis(), ins_counter);
}
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();