Browse Source

SITL: setup more defaults with flightaxis

with copters now you only need to set FRAME_CLASS to fly
mission-4.1.18
Andrew Tridgell 7 years ago
parent
commit
dc54babe41
  1. 17
      libraries/SITL/SIM_FlightAxis.cpp

17
libraries/SITL/SIM_FlightAxis.cpp

@ -40,9 +40,19 @@ using namespace SITL;
static const struct { static const struct {
const char *name; const char *name;
float value; float value;
bool save;
} sim_defaults[] = { } sim_defaults[] = {
{ "AHRS_EKF_TYPE", 10 }, { "AHRS_EKF_TYPE", 10 },
{ "INS_GYR_CAL", 0 }, { "INS_GYR_CAL", 0 },
{ "RC1_MIN", 1000, true },
{ "RC1_MAX", 2000, true },
{ "RC2_MIN", 1000, true },
{ "RC2_MAX", 2000, true },
{ "RC3_MIN", 1000, true },
{ "RC3_MAX", 2000, true },
{ "RC4_MIN", 1000, true },
{ "RC4_MAX", 2000, true },
{ "RC2_REVERSED", 1 }, // interlink has reversed rc2
{ "SERVO1_MIN", 1000 }, { "SERVO1_MIN", 1000 },
{ "SERVO1_MAX", 2000 }, { "SERVO1_MAX", 2000 },
{ "SERVO2_MIN", 1000 }, { "SERVO2_MIN", 1000 },
@ -85,6 +95,13 @@ FlightAxis::FlightAxis(const char *home_str, const char *frame_str) :
} }
for (uint8_t i=0; i<ARRAY_SIZE(sim_defaults); i++) { for (uint8_t i=0; i<ARRAY_SIZE(sim_defaults); i++) {
AP_Param::set_default_by_name(sim_defaults[i].name, sim_defaults[i].value); AP_Param::set_default_by_name(sim_defaults[i].name, sim_defaults[i].value);
if (sim_defaults[i].save) {
enum ap_var_type ptype;
AP_Param *p = AP_Param::find(sim_defaults[i].name, &ptype);
if (!p->configured()) {
p->save();
}
}
} }
/* Create the thread that will be waiting for data from FlightAxis */ /* Create the thread that will be waiting for data from FlightAxis */

Loading…
Cancel
Save