From dc54babe4138054484979ca1866ca77ac92fcdfd Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 13 Jul 2018 09:47:27 +1000 Subject: [PATCH] SITL: setup more defaults with flightaxis with copters now you only need to set FRAME_CLASS to fly --- libraries/SITL/SIM_FlightAxis.cpp | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/libraries/SITL/SIM_FlightAxis.cpp b/libraries/SITL/SIM_FlightAxis.cpp index 8e72a789ca..1dab6f8a5a 100644 --- a/libraries/SITL/SIM_FlightAxis.cpp +++ b/libraries/SITL/SIM_FlightAxis.cpp @@ -40,9 +40,19 @@ using namespace SITL; static const struct { const char *name; float value; + bool save; } sim_defaults[] = { { "AHRS_EKF_TYPE", 10 }, { "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_MAX", 2000 }, { "SERVO2_MIN", 1000 }, @@ -85,6 +95,13 @@ FlightAxis::FlightAxis(const char *home_str, const char *frame_str) : } for (uint8_t i=0; iconfigured()) { + p->save(); + } + } } /* Create the thread that will be waiting for data from FlightAxis */