APM:Libraries
Scheduler_test.cpp
Go to the documentation of this file.
1 //
2 // Simple test for the AP_Scheduler interface
3 //
4 
5 #include <AP_HAL/AP_HAL.h>
9 #include <DataFlash/DataFlash.h>
10 
12 
13 AP_Int32 log_bitmask;
15 
16 class SchedTest {
17 public:
18  void setup();
19  void loop();
20 
21 private:
22 
25 
26  uint32_t ins_counter;
28 
29  void ins_update(void);
30  void one_hz_print(void);
31  void five_second_call(void);
32 };
33 
36 
37 #define SCHED_TASK(func, _interval_ticks, _max_time_micros) SCHED_TASK_CLASS(SchedTest, &schedtest, func, _interval_ticks, _max_time_micros)
38 
39 /*
40  scheduler table - all regular tasks are listed here, along with how
41  often they should be called (in 20ms units) and the maximum time
42  they are expected to take (in microseconds)
43  */
45  SCHED_TASK(ins_update, 50, 1000),
46  SCHED_TASK(one_hz_print, 1, 1000),
47  SCHED_TASK(five_second_call, 0.2, 1800),
48 };
49 
50 
51 void SchedTest::setup(void)
52 {
53 
54  board_config.init();
55 
57 
58  // initialise the scheduler
60 }
61 
62 void SchedTest::loop(void)
63 {
64  // run all tasks
65  scheduler.loop();
66 }
67 
68 /*
69  update inertial sensor, reading data
70  */
72 {
73  ins_counter++;
74  ins.update();
75 }
76 
77 /*
78  print something once a second
79  */
81 {
82  hal.console->printf("one_hz: t=%lu\n", (unsigned long)AP_HAL::millis());
83 }
84 
85 /*
86  print something every 5 seconds
87  */
89 {
90  hal.console->printf("five_seconds: t=%lu ins_counter=%u\n", (unsigned long)AP_HAL::millis(), (unsigned)ins_counter);
91 }
92 
93 /*
94  compatibility with old pde style build
95  */
96 void setup(void);
97 void loop(void);
98 
99 void setup(void)
100 {
101  schedtest.setup();
102 }
103 void loop(void)
104 {
105  schedtest.loop();
106 }
107 AP_HAL_MAIN();
void five_second_call(void)
AP_HAL::UARTDriver * console
Definition: HAL.h:110
uint16_t get_loop_rate_hz(void)
Definition: AP_Scheduler.h:110
#define SCHED_TASK(func, _interval_ticks, _max_time_micros)
void init(const Task *tasks, uint8_t num_tasks, uint32_t log_performance_bit)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
AP_InertialSensor ins
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
uint32_t millis()
Definition: system.cpp:157
void ins_update(void)
static SchedTest schedtest
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
const HAL & get_HAL()
uint32_t ins_counter
AP_Int32 log_bitmask
AP_HAL_MAIN()
DataFlash_Class DataFlash
void init(uint16_t sample_rate_hz)
AP_Scheduler scheduler
static AP_BoardConfig board_config
void one_hz_print(void)
static const AP_Scheduler::Task scheduler_tasks[]