AP_Scheduler: fixed example test to pass/fail

This commit is contained in:
Andrew Tridgell 2024-02-23 11:59:56 +11:00
parent 7226c5107d
commit 09500df4a8

View File

@ -9,6 +9,7 @@
#include <AP_BoardConfig/AP_BoardConfig.h> #include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_Logger/AP_Logger.h> #include <AP_Logger/AP_Logger.h>
#include <GCS_MAVLink/GCS_Dummy.h> #include <GCS_MAVLink/GCS_Dummy.h>
#include <stdio.h>
const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
AP_GROUPEND AP_GROUPEND
@ -26,13 +27,14 @@ public:
private: private:
AP_InertialSensor ins;
#if HAL_EXTERNAL_AHRS_ENABLED #if HAL_EXTERNAL_AHRS_ENABLED
AP_ExternalAHRS eAHRS; AP_ExternalAHRS eAHRS;
#endif // HAL_EXTERNAL_AHRS_ENABLED #endif // HAL_EXTERNAL_AHRS_ENABLED
AP_Scheduler scheduler; AP_Scheduler scheduler;
uint32_t ins_counter; uint32_t ins_counter;
uint32_t count_5s;
uint32_t count_1s;
static const AP_Scheduler::Task scheduler_tasks[]; static const AP_Scheduler::Task scheduler_tasks[];
void ins_update(void); void ins_update(void);
@ -81,8 +83,6 @@ void SchedTest::setup(void)
board_config.init(); board_config.init();
ins.init(scheduler.get_loop_rate_hz());
// initialise the scheduler // initialise the scheduler
scheduler.init(&scheduler_tasks[0], ARRAY_SIZE(scheduler_tasks), (uint32_t)-1); scheduler.init(&scheduler_tasks[0], ARRAY_SIZE(scheduler_tasks), (uint32_t)-1);
} }
@ -91,6 +91,24 @@ void SchedTest::loop(void)
{ {
// run all tasks // run all tasks
scheduler.loop(); scheduler.loop();
if (ins_counter == 1000) {
bool ok = true;
if (count_5s != 4) {
::printf("ERROR: count_5s=%u\n", (unsigned)count_5s);
ok = false;
}
if (count_1s != 20) {
::printf("ERROR: count_1s=%u\n", (unsigned)count_1s);
ok = false;
}
if (!ok) {
::printf("Test FAILED\n");
exit(1);
} else {
::printf("Test PASSED\n");
exit(0);
}
}
} }
/* /*
@ -99,7 +117,6 @@ void SchedTest::loop(void)
void SchedTest::ins_update(void) void SchedTest::ins_update(void)
{ {
ins_counter++; ins_counter++;
ins.update();
} }
/* /*
@ -108,6 +125,7 @@ void SchedTest::ins_update(void)
void SchedTest::one_hz_print(void) void SchedTest::one_hz_print(void)
{ {
hal.console->printf("one_hz: t=%lu\n", (unsigned long)AP_HAL::millis()); hal.console->printf("one_hz: t=%lu\n", (unsigned long)AP_HAL::millis());
count_1s++;
} }
/* /*
@ -116,6 +134,7 @@ void SchedTest::one_hz_print(void)
void SchedTest::five_second_call(void) void SchedTest::five_second_call(void)
{ {
hal.console->printf("five_seconds: t=%lu ins_counter=%u\n", (unsigned long)AP_HAL::millis(), (unsigned)ins_counter); hal.console->printf("five_seconds: t=%lu ins_counter=%u\n", (unsigned long)AP_HAL::millis(), (unsigned)ins_counter);
count_5s++;
} }
/* /*
@ -128,8 +147,10 @@ void setup(void)
{ {
schedtest.setup(); schedtest.setup();
} }
void loop(void) void loop(void)
{ {
schedtest.loop(); schedtest.loop();
} }
AP_HAL_MAIN(); AP_HAL_MAIN();