mirror of https://github.com/ArduPilot/ardupilot
SITL: use AP_JSON
This commit is contained in:
parent
a3697b3d97
commit
cb01789b9f
|
@ -35,10 +35,8 @@
|
||||||
#include <AP_Terrain/AP_Terrain.h>
|
#include <AP_Terrain/AP_Terrain.h>
|
||||||
#include <AP_Scheduler/AP_Scheduler.h>
|
#include <AP_Scheduler/AP_Scheduler.h>
|
||||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
#if USE_PICOJSON
|
#include <AP_JSON/AP_JSON.h>
|
||||||
#include "picojson.h"
|
|
||||||
#include <AP_Filesystem/AP_Filesystem.h>
|
#include <AP_Filesystem/AP_Filesystem.h>
|
||||||
#endif
|
|
||||||
|
|
||||||
using namespace SITL;
|
using namespace SITL;
|
||||||
|
|
||||||
|
|
|
@ -38,10 +38,6 @@
|
||||||
#include <Filter/Filter.h>
|
#include <Filter/Filter.h>
|
||||||
#include "SIM_JSON_Master.h"
|
#include "SIM_JSON_Master.h"
|
||||||
|
|
||||||
#ifndef USE_PICOJSON
|
|
||||||
#define USE_PICOJSON (CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX)
|
|
||||||
#endif
|
|
||||||
|
|
||||||
namespace SITL {
|
namespace SITL {
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -331,7 +331,6 @@ float Frame::get_air_density(float alt_amsl) const
|
||||||
return air_pressure / (ISA_GAS_CONSTANT * (C_TO_KELVIN(model.refTempC)));
|
return air_pressure / (ISA_GAS_CONSTANT * (C_TO_KELVIN(model.refTempC)));
|
||||||
}
|
}
|
||||||
|
|
||||||
#if USE_PICOJSON
|
|
||||||
/*
|
/*
|
||||||
load frame specific parameters from a json file if available
|
load frame specific parameters from a json file if available
|
||||||
*/
|
*/
|
||||||
|
@ -350,7 +349,7 @@ void Frame::load_frame_params(const char *model_json)
|
||||||
if (fname == nullptr) {
|
if (fname == nullptr) {
|
||||||
AP_HAL::panic("%s failed to load\n", model_json);
|
AP_HAL::panic("%s failed to load\n", model_json);
|
||||||
}
|
}
|
||||||
picojson::value *obj = (picojson::value *)load_json(model_json);
|
AP_JSON::value *obj = AP_JSON::load_json(model_json);
|
||||||
if (obj == nullptr) {
|
if (obj == nullptr) {
|
||||||
AP_HAL::panic("%s failed to load\n", model_json);
|
AP_HAL::panic("%s failed to load\n", model_json);
|
||||||
}
|
}
|
||||||
|
@ -395,7 +394,7 @@ void Frame::load_frame_params(const char *model_json)
|
||||||
|
|
||||||
for (uint8_t i=0; i<ARRAY_SIZE(vars); i++) {
|
for (uint8_t i=0; i<ARRAY_SIZE(vars); i++) {
|
||||||
auto v = obj->get(vars[i].label);
|
auto v = obj->get(vars[i].label);
|
||||||
if (v.is<picojson::null>()) {
|
if (v.is<AP_JSON::null>()) {
|
||||||
// use default value
|
// use default value
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
@ -418,7 +417,7 @@ void Frame::load_frame_params(const char *model_json)
|
||||||
for (uint8_t j=0; j<12; j++) {
|
for (uint8_t j=0; j<12; j++) {
|
||||||
snprintf(label_name, 20, "motor%i_%s", j+1, per_motor_vars[i].label);
|
snprintf(label_name, 20, "motor%i_%s", j+1, per_motor_vars[i].label);
|
||||||
auto v = obj->get(label_name);
|
auto v = obj->get(label_name);
|
||||||
if (v.is<picojson::null>()) {
|
if (v.is<AP_JSON::null>()) {
|
||||||
// use default value
|
// use default value
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
@ -436,15 +435,15 @@ void Frame::load_frame_params(const char *model_json)
|
||||||
::printf("Loaded model params from %s\n", model_json);
|
::printf("Loaded model params from %s\n", model_json);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Frame::parse_float(picojson::value val, const char* label, float ¶m) {
|
void Frame::parse_float(AP_JSON::value val, const char* label, float ¶m) {
|
||||||
if (!val.is<double>()) {
|
if (!val.is<double>()) {
|
||||||
AP_HAL::panic("Bad json type for %s: %s", label, val.to_str().c_str());
|
AP_HAL::panic("Bad json type for %s: %s", label, val.to_str().c_str());
|
||||||
}
|
}
|
||||||
param = val.get<double>();
|
param = val.get<double>();
|
||||||
}
|
}
|
||||||
|
|
||||||
void Frame::parse_vector3(picojson::value val, const char* label, Vector3f ¶m) {
|
void Frame::parse_vector3(AP_JSON::value val, const char* label, Vector3f ¶m) {
|
||||||
if (!val.is<picojson::array>() || !val.contains(2) || val.contains(3)) {
|
if (!val.is<AP_JSON::value::array>() || !val.contains(2) || val.contains(3)) {
|
||||||
AP_HAL::panic("Bad json type for %s: %s", label, val.to_str().c_str());
|
AP_HAL::panic("Bad json type for %s: %s", label, val.to_str().c_str());
|
||||||
}
|
}
|
||||||
for (uint8_t j=0; j<3; j++) {
|
for (uint8_t j=0; j<3; j++) {
|
||||||
|
@ -452,8 +451,6 @@ void Frame::parse_vector3(picojson::value val, const char* label, Vector3f ¶
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if AP_SIM_ENABLED
|
#if AP_SIM_ENABLED
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -464,13 +461,11 @@ void Frame::init(const char *frame_str, Battery *_battery)
|
||||||
model = default_model;
|
model = default_model;
|
||||||
battery = _battery;
|
battery = _battery;
|
||||||
|
|
||||||
#if USE_PICOJSON
|
|
||||||
const char *colon = strchr(frame_str, ':');
|
const char *colon = strchr(frame_str, ':');
|
||||||
size_t slen = strlen(frame_str);
|
size_t slen = strlen(frame_str);
|
||||||
if (colon != nullptr && slen > 5 && strcmp(&frame_str[slen-5], ".json") == 0) {
|
if (colon != nullptr && slen > 5 && strcmp(&frame_str[slen-5], ".json") == 0) {
|
||||||
load_frame_params(colon+1);
|
load_frame_params(colon+1);
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
mass = model.mass;
|
mass = model.mass;
|
||||||
|
|
||||||
const float drag_force = model.mass * GRAVITY_MSS * tanf(radians(model.refAngle));
|
const float drag_force = model.mass * GRAVITY_MSS * tanf(radians(model.refAngle));
|
||||||
|
|
|
@ -20,10 +20,7 @@
|
||||||
|
|
||||||
#include "SIM_Aircraft.h"
|
#include "SIM_Aircraft.h"
|
||||||
#include "SIM_Motor.h"
|
#include "SIM_Motor.h"
|
||||||
|
#include <AP_JSON/AP_JSON.h>
|
||||||
#if USE_PICOJSON
|
|
||||||
#include "picojson.h"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
namespace SITL {
|
namespace SITL {
|
||||||
|
|
||||||
|
@ -146,10 +143,8 @@ private:
|
||||||
} default_model;
|
} default_model;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
#if USE_PICOJSON
|
|
||||||
// load frame parameters from a json model file
|
// load frame parameters from a json model file
|
||||||
void load_frame_params(const char *model_json);
|
void load_frame_params(const char *model_json);
|
||||||
#endif
|
|
||||||
|
|
||||||
// get air density in kg/m^3
|
// get air density in kg/m^3
|
||||||
float get_air_density(float alt_amsl) const;
|
float get_air_density(float alt_amsl) const;
|
||||||
|
@ -166,9 +161,7 @@ private:
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// json parsing helpers
|
// json parsing helpers
|
||||||
#if USE_PICOJSON
|
void parse_float(AP_JSON::value val, const char* label, float ¶m);
|
||||||
void parse_float(picojson::value val, const char* label, float ¶m);
|
void parse_vector3(AP_JSON::value val, const char* label, Vector3f ¶m);
|
||||||
void parse_vector3(picojson::value val, const char* label, Vector3f ¶m);
|
|
||||||
#endif
|
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
|
@ -30,7 +30,6 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Filesystem/AP_Filesystem.h>
|
#include <AP_Filesystem/AP_Filesystem.h>
|
||||||
#include <SRV_Channel/SRV_Channel.h>
|
#include <SRV_Channel/SRV_Channel.h>
|
||||||
#include "picojson.h"
|
|
||||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||||
|
|
||||||
// ignore cast errors in this case to keep complexity down
|
// ignore cast errors in this case to keep complexity down
|
||||||
|
@ -124,7 +123,7 @@ XPlane::XPlane(const char *frame_str) :
|
||||||
/*
|
/*
|
||||||
add one DRef to list
|
add one DRef to list
|
||||||
*/
|
*/
|
||||||
void XPlane::add_dref(const char *name, DRefType type, const picojson::value &dref)
|
void XPlane::add_dref(const char *name, DRefType type, const AP_JSON::value &dref)
|
||||||
{
|
{
|
||||||
struct DRef *d = new struct DRef;
|
struct DRef *d = new struct DRef;
|
||||||
if (d == nullptr) {
|
if (d == nullptr) {
|
||||||
|
@ -149,7 +148,7 @@ void XPlane::add_dref(const char *name, DRefType type, const picojson::value &dr
|
||||||
/*
|
/*
|
||||||
add one joystick axis to list
|
add one joystick axis to list
|
||||||
*/
|
*/
|
||||||
void XPlane::add_joyinput(const char *label, JoyType type, const picojson::value &d)
|
void XPlane::add_joyinput(const char *label, JoyType type, const AP_JSON::value &d)
|
||||||
{
|
{
|
||||||
if (strncmp(label, "axis", 4) == 0) {
|
if (strncmp(label, "axis", 4) == 0) {
|
||||||
struct JoyInput *j = new struct JoyInput;
|
struct JoyInput *j = new struct JoyInput;
|
||||||
|
@ -180,7 +179,7 @@ void XPlane::add_joyinput(const char *label, JoyType type, const picojson::value
|
||||||
/*
|
/*
|
||||||
handle a setting
|
handle a setting
|
||||||
*/
|
*/
|
||||||
void XPlane::handle_setting(const picojson::value &d)
|
void XPlane::handle_setting(const AP_JSON::value &d)
|
||||||
{
|
{
|
||||||
if (d.contains("debug")) {
|
if (d.contains("debug")) {
|
||||||
dref_debug = d.get("debug").get<double>();
|
dref_debug = d.get("debug").get<double>();
|
||||||
|
@ -205,7 +204,7 @@ bool XPlane::load_dref_map(const char *map_json)
|
||||||
if (fname == nullptr) {
|
if (fname == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
picojson::value *obj = (picojson::value *)load_json(fname);
|
AP_JSON::value *obj = AP_JSON::load_json(fname);
|
||||||
if (obj == nullptr) {
|
if (obj == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
@ -230,8 +229,8 @@ bool XPlane::load_dref_map(const char *map_json)
|
||||||
|
|
||||||
uint32_t count = 0;
|
uint32_t count = 0;
|
||||||
// obtain a const reference to the map, and print the contents
|
// obtain a const reference to the map, and print the contents
|
||||||
const picojson::value::object& o = obj->get<picojson::object>();
|
const AP_JSON::value::object& o = obj->get<AP_JSON::value::object>();
|
||||||
for (picojson::value::object::const_iterator i = o.begin();
|
for (AP_JSON::value::object::const_iterator i = o.begin();
|
||||||
i != o.end();
|
i != o.end();
|
||||||
++i) {
|
++i) {
|
||||||
const char *label = i->first.c_str();
|
const char *label = i->first.c_str();
|
||||||
|
|
|
@ -30,7 +30,7 @@
|
||||||
#include <AP_Filesystem/AP_Filesystem.h>
|
#include <AP_Filesystem/AP_Filesystem.h>
|
||||||
|
|
||||||
#include "SIM_Aircraft.h"
|
#include "SIM_Aircraft.h"
|
||||||
#include "picojson.h"
|
#include <AP_JSON/AP_JSON.h>
|
||||||
|
|
||||||
namespace SITL {
|
namespace SITL {
|
||||||
|
|
||||||
|
@ -126,9 +126,9 @@ private:
|
||||||
struct stat map_st;
|
struct stat map_st;
|
||||||
|
|
||||||
bool load_dref_map(const char *map_json);
|
bool load_dref_map(const char *map_json);
|
||||||
void add_dref(const char *name, DRefType type, const picojson::value &dref);
|
void add_dref(const char *name, DRefType type, const AP_JSON::value &dref);
|
||||||
void add_joyinput(const char *name, JoyType type, const picojson::value &d);
|
void add_joyinput(const char *name, JoyType type, const AP_JSON::value &d);
|
||||||
void handle_setting(const picojson::value &d);
|
void handle_setting(const AP_JSON::value &d);
|
||||||
|
|
||||||
void check_reload_dref(void);
|
void check_reload_dref(void);
|
||||||
|
|
||||||
|
|
|
@ -9,9 +9,6 @@ def build(bld):
|
||||||
source = bld.path.ant_glob('*.cpp')
|
source = bld.path.ant_glob('*.cpp')
|
||||||
source.append('../../../../libraries/SITL/SIM_Battery.cpp')
|
source.append('../../../../libraries/SITL/SIM_Battery.cpp')
|
||||||
source.append('../../../../libraries/SITL/SIM_Frame.cpp')
|
source.append('../../../../libraries/SITL/SIM_Frame.cpp')
|
||||||
source.append('../../../../libraries/SITL/picojson.cpp')
|
|
||||||
|
|
||||||
bld.env.DEFINES.append("USE_PICOJSON=1")
|
|
||||||
|
|
||||||
bld.ap_program(
|
bld.ap_program(
|
||||||
use='ap',
|
use='ap',
|
||||||
|
|
|
@ -9,9 +9,6 @@ def build(bld):
|
||||||
source = bld.path.ant_glob('*.cpp')
|
source = bld.path.ant_glob('*.cpp')
|
||||||
source.append('../../../../libraries/SITL/SIM_Motor.cpp')
|
source.append('../../../../libraries/SITL/SIM_Motor.cpp')
|
||||||
source.append('../../../../libraries/SITL/SIM_Frame.cpp')
|
source.append('../../../../libraries/SITL/SIM_Frame.cpp')
|
||||||
source.append('../../../../libraries/SITL/picojson.cpp')
|
|
||||||
|
|
||||||
bld.env.DEFINES.append("USE_PICOJSON=1")
|
|
||||||
|
|
||||||
bld.ap_program(
|
bld.ap_program(
|
||||||
use='ap',
|
use='ap',
|
||||||
|
|
|
@ -1,62 +0,0 @@
|
||||||
|
|
||||||
#include "SIM_Aircraft.h"
|
|
||||||
#include <AP_Filesystem/AP_Filesystem.h>
|
|
||||||
|
|
||||||
#if USE_PICOJSON
|
|
||||||
#include "picojson.h"
|
|
||||||
|
|
||||||
/*
|
|
||||||
load JSON file, returning a picojson object or nullptr on failure
|
|
||||||
*/
|
|
||||||
void *load_json(const char *filename)
|
|
||||||
{
|
|
||||||
struct stat st;
|
|
||||||
if (AP::FS().stat(filename, &st) != 0) {
|
|
||||||
::printf("No such json file %s\n", filename);
|
|
||||||
return nullptr;
|
|
||||||
}
|
|
||||||
int fd = AP::FS().open(filename, O_RDONLY);
|
|
||||||
if (fd == -1) {
|
|
||||||
::printf("failed to open json %s\n", filename);
|
|
||||||
return nullptr;
|
|
||||||
}
|
|
||||||
char buf[st.st_size+1];
|
|
||||||
memset(buf, '\0', sizeof(buf));
|
|
||||||
if (AP::FS().read(fd, buf, st.st_size) != st.st_size) {
|
|
||||||
::printf("failed to read json %s\n", filename);
|
|
||||||
AP::FS().close(fd);
|
|
||||||
return nullptr;
|
|
||||||
}
|
|
||||||
AP::FS().close(fd);
|
|
||||||
|
|
||||||
char *start = strchr(buf, '{');
|
|
||||||
if (!start) {
|
|
||||||
::printf("Invalid json %s", filename);
|
|
||||||
return nullptr;
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
|
||||||
remove comments, as not allowed by the parser
|
|
||||||
*/
|
|
||||||
for (char *p = strchr(start,'#'); p; p=strchr(p+1, '#')) {
|
|
||||||
// clear to end of line
|
|
||||||
do {
|
|
||||||
*p++ = ' ';
|
|
||||||
} while (*p != '\n' && *p != '\r' && *p);
|
|
||||||
}
|
|
||||||
|
|
||||||
picojson::value *obj = new picojson::value;
|
|
||||||
if (obj == nullptr) {
|
|
||||||
::printf("Invalid allocate json for %s", filename);
|
|
||||||
return nullptr;
|
|
||||||
}
|
|
||||||
std::string err = picojson::parse(*obj, start);
|
|
||||||
if (!err.empty()) {
|
|
||||||
::printf("parse failed for json %s", filename);
|
|
||||||
delete obj;
|
|
||||||
return nullptr;
|
|
||||||
}
|
|
||||||
|
|
||||||
return obj;
|
|
||||||
}
|
|
||||||
#endif // USE_PICOJSON
|
|
File diff suppressed because it is too large
Load Diff
Loading…
Reference in New Issue