Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

CI: get more examples working #26296

Merged
merged 9 commits into from
Feb 28, 2024
Merged
2 changes: 1 addition & 1 deletion Tools/autotest/examples.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ def run_example(filepath, valgrind=False, gdb=False):


def run_examples(debug=False, valgrind=False, gdb=False):
dirpath = util.reltopdir(os.path.join('build', 'linux', 'examples'))
dirpath = util.reltopdir(os.path.join('build', 'sitl', 'examples'))

print("Running Hello")
# explicitly run helloworld and check for output
Expand Down
2 changes: 1 addition & 1 deletion Tools/scripts/build_ci.sh
Original file line number Diff line number Diff line change
Expand Up @@ -176,7 +176,7 @@ for t in $CI_BUILD_TARGET; do
fi

if [ "$t" == "examples" ]; then
./waf configure --board=linux --debug
./waf configure --board=sitl --debug
./waf examples
run_autotest "Examples" "--no-clean" "run.examples"
continue
Expand Down
10 changes: 6 additions & 4 deletions libraries/AP_HAL_SITL/SITL_cmdline.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
#include <SITL/SIM_Webots_Python.h>
#include <SITL/SIM_JSON.h>
#include <SITL/SIM_Blimp.h>
#include <SITL/SIM_NoVehicle.h>
#include <AP_Filesystem/AP_Filesystem.h>

#include <AP_Vehicle/AP_Vehicle_Type.h>
Expand Down Expand Up @@ -181,6 +182,7 @@ static const struct {
{ "webots", Webots::create },
{ "JSON", JSON::create },
{ "blimp", Blimp::create },
{ "novehicle", NoVehicle::create },
};

void SITL_State::_set_signal_handlers(void) const
Expand Down Expand Up @@ -239,7 +241,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
static struct timeval first_tv;
gettimeofday(&first_tv, nullptr);
time_t start_time_UTC = first_tv.tv_sec;
const bool is_replay = APM_BUILD_TYPE(APM_BUILD_Replay);
const bool is_example = APM_BUILD_TYPE(APM_BUILD_Replay) || APM_BUILD_TYPE(APM_BUILD_UNKNOWN);

enum long_options {
CMDLINE_GIMBAL = 1,
Expand Down Expand Up @@ -348,8 +350,8 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
{0, false, 0, 0}
};

if (is_replay) {
model_str = "quad";
if (is_example) {
model_str = "novehicle";
HALSITL::UARTDriver::_console = true;
}

Expand All @@ -371,7 +373,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])

GetOptLong gopt(argc, argv, "hwus:r:CI:P:SO:M:F:c:v:",
options);
while (!is_replay && (opt = gopt.getoption()) != -1) {
while (!is_example && (opt = gopt.getoption()) != -1) {
switch (opt) {
case 'w':
erase_all_storage = true;
Expand Down
7 changes: 6 additions & 1 deletion libraries/AP_HAL_SITL/Scheduler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,11 @@ bool Scheduler::semaphore_wait_hack_required() const

void Scheduler::delay_microseconds(uint16_t usec)
{
if (_sitlState->_sitl == nullptr) {
// this allows examples to run
hal.scheduler->stop_clock(AP_HAL::micros64()+usec);
return;
}
uint64_t start = AP_HAL::micros64();
do {
uint64_t dtime = AP_HAL::micros64() - start;
Expand Down Expand Up @@ -296,7 +301,7 @@ void Scheduler::_run_io_procs()
void Scheduler::stop_clock(uint64_t time_usec)
{
_stopped_clock_usec = time_usec;
if (time_usec - _last_io_run > 10000) {
if (_sitlState->_sitl != nullptr && time_usec - _last_io_run > 10000) {
_last_io_run = time_usec;
_run_io_procs();
}
Expand Down
7 changes: 7 additions & 0 deletions libraries/AP_InertialSensor/AP_InertialSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1973,6 +1973,13 @@ void AP_InertialSensor::update(void)
*/
void AP_InertialSensor::wait_for_sample(void)
{
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
auto *sitl = AP::sitl();
if (sitl == nullptr) {
hal.scheduler->delay_microseconds(1000);
return;
}
#endif
if (_have_sample) {
// the user has called wait_for_sample() again without
// consuming the sample with update()
Expand Down
21 changes: 18 additions & 3 deletions libraries/AP_JSON/examples/XPlane/XPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,16 @@ void loop();

const AP_HAL::HAL& hal = AP_HAL::get_HAL();

static void test_xplane(void)
static uint32_t test_count;
static uint32_t label_count;

static bool test_xplane(void)
{
const uint32_t m1 = hal.util->available_memory();
auto *obj = AP_JSON::load_json("@ROMFS/models/xplane_plane.json");
if (obj == nullptr) {
::printf("Failed to parse json\n");
::printf("Failed to load or parse json\n");
return false;
}
const uint32_t m2 = hal.util->available_memory();
::printf("Used %u bytes\n", unsigned(m1-m2));
Expand All @@ -28,8 +32,10 @@ static void test_xplane(void)
++i) {
const char *label = i->first.c_str();
::printf("Label: %s\n", label);
label_count++;
}
delete obj;
return label_count > 10;
}

/*
Expand All @@ -43,7 +49,16 @@ void setup(void)
void loop(void)
{
::printf("Memory: %u\n", (unsigned)hal.util->available_memory());
test_xplane();
if (test_xplane()) {
test_count++;
} else {
::printf("Test FAILED\n");
exit(1);
}
if (test_count > 10) {
::printf("Test PASSED\n");
exit(0);
}
}

AP_HAL_MAIN();
2 changes: 1 addition & 1 deletion libraries/AP_Scheduler/AP_Scheduler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -360,7 +360,7 @@ void AP_Scheduler::loop()
for testing low CPU conditions we can add an optional delay in SITL
*/
auto *sitl = AP::sitl();
uint32_t loop_delay_us = sitl->loop_delay.get();
uint32_t loop_delay_us = sitl? sitl->loop_delay.get() : 1000U;
hal.scheduler->delay_microseconds(loop_delay_us);
}
#endif
Expand Down
29 changes: 25 additions & 4 deletions libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_Logger/AP_Logger.h>
#include <GCS_MAVLink/GCS_Dummy.h>
#include <stdio.h>

const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
AP_GROUPEND
Expand All @@ -26,13 +27,14 @@ class SchedTest {

private:

AP_InertialSensor ins;
#if HAL_EXTERNAL_AHRS_ENABLED
AP_ExternalAHRS eAHRS;
#endif // HAL_EXTERNAL_AHRS_ENABLED
AP_Scheduler scheduler;

uint32_t ins_counter;
uint32_t count_5s;
uint32_t count_1s;
static const AP_Scheduler::Task scheduler_tasks[];

void ins_update(void);
Expand Down Expand Up @@ -81,8 +83,6 @@ void SchedTest::setup(void)

board_config.init();

ins.init(scheduler.get_loop_rate_hz());

// initialise the scheduler
scheduler.init(&scheduler_tasks[0], ARRAY_SIZE(scheduler_tasks), (uint32_t)-1);
}
Expand All @@ -91,6 +91,24 @@ void SchedTest::loop(void)
{
// run all tasks
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);
}
}
}

/*
Expand All @@ -99,7 +117,6 @@ void SchedTest::loop(void)
void SchedTest::ins_update(void)
{
ins_counter++;
ins.update();
}

/*
Expand All @@ -108,6 +125,7 @@ void SchedTest::ins_update(void)
void SchedTest::one_hz_print(void)
{
hal.console->printf("one_hz: t=%lu\n", (unsigned long)AP_HAL::millis());
count_1s++;
}

/*
Expand All @@ -116,6 +134,7 @@ void SchedTest::one_hz_print(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);
count_5s++;
}

/*
Expand All @@ -128,8 +147,10 @@ void setup(void)
{
schedtest.setup();
}

void loop(void)
{
schedtest.loop();
}

AP_HAL_MAIN();
40 changes: 40 additions & 0 deletions libraries/SITL/SIM_NoVehicle.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.

This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.

You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
empty vehicle for example CI testing
*/

#pragma once

#include "SIM_Aircraft.h"

namespace SITL {

/*
empty vehicle
*/
class NoVehicle : public Aircraft {
public:
NoVehicle(const char *frame_str) : Aircraft(frame_str) {}

void update(const struct sitl_input &input) override {}

/* static object creator */
static Aircraft *create(const char *frame_str) {
return new NoVehicle(frame_str);
}
};

} // namespace SITL
Loading