diff --git a/libraries/AP_HAL_SITL/SITL_State_common.cpp b/libraries/AP_HAL_SITL/SITL_State_common.cpp index 320fcf9615..10b2103fb0 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.cpp +++ b/libraries/AP_HAL_SITL/SITL_State_common.cpp @@ -233,6 +233,12 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const sitl_model->set_ie24(&_sitl->ie24_sim); return &_sitl->ie24_sim; #endif // HAL_BUILD_AP_PERIPH + } else if (streq(name, "jre")) { + if (jre != nullptr) { + AP_HAL::panic("Only one jre at a time"); + } + jre = new SITL::RF_JRE(); + return jre; } else if (streq(name, "gyus42v2")) { if (gyus42v2 != nullptr) { AP_HAL::panic("Only one gyus42v2 at a time"); @@ -315,6 +321,9 @@ void SITL_State_Common::sim_update(void) if (benewake_tfmini != nullptr) { benewake_tfmini->update(sitl_model->rangefinder_range()); } + if (jre != nullptr) { + jre->update(sitl_model->rangefinder_range()); + } if (nooploop != nullptr) { nooploop->update(sitl_model->rangefinder_range()); } diff --git a/libraries/AP_HAL_SITL/SITL_State_common.h b/libraries/AP_HAL_SITL/SITL_State_common.h index dab0cb0e5a..bed95fd9ce 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.h +++ b/libraries/AP_HAL_SITL/SITL_State_common.h @@ -17,6 +17,7 @@ #include #include #include +#include #include #include #include @@ -126,6 +127,8 @@ public: SITL::RF_Benewake_TF02 *benewake_tf02; // simulated Benewake tf03 rangefinder: SITL::RF_Benewake_TF03 *benewake_tf03; + //simulated JAE JRE rangefinder: + SITL::RF_JRE *jre; // simulated Benewake tfmini rangefinder: SITL::RF_Benewake_TFmini *benewake_tfmini; //simulated NoopLoop TOFSense rangefinder: