ardupilot/libraries/AP_JSON/examples/XPlane/XPlane.cpp

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

65 lines
1.3 KiB
C++
Raw Normal View History

2024-02-01 00:18:12 -04:00
//
// tests for the AP_JSON parser
//
#include <AP_HAL/AP_HAL.h>
#include <AP_JSON/AP_JSON.h>
#include <stdio.h>
void setup();
void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
2024-02-22 20:39:33 -04:00
static uint32_t test_count;
static uint32_t label_count;
static bool test_xplane(void)
2024-02-01 00:18:12 -04:00
{
const uint32_t m1 = hal.util->available_memory();
auto *obj = AP_JSON::load_json("@ROMFS/models/xplane_plane.json");
if (obj == nullptr) {
2024-02-22 20:39:33 -04:00
::printf("Failed to load or parse json\n");
return false;
2024-02-01 00:18:12 -04:00
}
const uint32_t m2 = hal.util->available_memory();
::printf("Used %u bytes\n", unsigned(m1-m2));
const AP_JSON::value::object& o = obj->get<AP_JSON::value::object>();
for (AP_JSON::value::object::const_iterator i = o.begin();
i != o.end();
++i) {
const char *label = i->first.c_str();
::printf("Label: %s\n", label);
2024-02-22 20:39:33 -04:00
label_count++;
2024-02-01 00:18:12 -04:00
}
delete obj;
2024-02-22 20:39:33 -04:00
return label_count > 10;
2024-02-01 00:18:12 -04:00
}
/*
* euler angle tests
*/
void setup(void)
{
hal.console->printf("AP_JSON tests\n");
}
void loop(void)
{
::printf("Memory: %u\n", (unsigned)hal.util->available_memory());
2024-02-22 20:39:33 -04:00
if (test_xplane()) {
test_count++;
} else {
::printf("Test FAILED\n");
exit(1);
}
if (test_count > 10) {
::printf("Test PASSED\n");
exit(0);
}
2024-02-01 00:18:12 -04:00
}
AP_HAL_MAIN();