From 7be9773f955d810e1fa3b90f92defa8b11cc207d Mon Sep 17 00:00:00 2001 From: Gone4Dirt Date: Tue, 10 Aug 2021 12:59:10 +0100 Subject: [PATCH] SITL: Update RPM param in FlightAxis defaults --- libraries/SITL/SIM_FlightAxis.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/SITL/SIM_FlightAxis.cpp b/libraries/SITL/SIM_FlightAxis.cpp index 9438501780..11a0299dbe 100644 --- a/libraries/SITL/SIM_FlightAxis.cpp +++ b/libraries/SITL/SIM_FlightAxis.cpp @@ -80,7 +80,7 @@ static const struct { { "INS_ACCSCAL_X", 1.001 }, { "INS_ACCSCAL_Y", 1.001 }, { "INS_ACCSCAL_Z", 1.001 }, - { "RPM_TYPE", 10 }, + { "RPM1_TYPE", 10 }, };