AP_HAL_SITL: add simulator for RDS02UF rangefinder
This commit is contained in:
parent
6943ea59b1
commit
4ed4c2d554
@ -295,6 +295,12 @@ SITL::SerialDevice *SITL_State::create_serial_sim(const char *name, const char *
|
|||||||
}
|
}
|
||||||
leddarone = new SITL::RF_LeddarOne();
|
leddarone = new SITL::RF_LeddarOne();
|
||||||
return leddarone;
|
return leddarone;
|
||||||
|
} else if (streq(name, "rds02uf")) {
|
||||||
|
if (rds02uf != nullptr) {
|
||||||
|
AP_HAL::panic("Only one rds02uf at a time");
|
||||||
|
}
|
||||||
|
rds02uf = new SITL::RF_RDS02UF();
|
||||||
|
return rds02uf;
|
||||||
} else if (streq(name, "USD1_v0")) {
|
} else if (streq(name, "USD1_v0")) {
|
||||||
if (USD1_v0 != nullptr) {
|
if (USD1_v0 != nullptr) {
|
||||||
AP_HAL::panic("Only one USD1_v0 at a time");
|
AP_HAL::panic("Only one USD1_v0 at a time");
|
||||||
@ -622,6 +628,9 @@ void SITL_State::_fdm_input_local(void)
|
|||||||
if (leddarone != nullptr) {
|
if (leddarone != nullptr) {
|
||||||
leddarone->update(sitl_model->rangefinder_range());
|
leddarone->update(sitl_model->rangefinder_range());
|
||||||
}
|
}
|
||||||
|
if (rds02uf != nullptr) {
|
||||||
|
rds02uf->update(sitl_model->rangefinder_range());
|
||||||
|
}
|
||||||
if (USD1_v0 != nullptr) {
|
if (USD1_v0 != nullptr) {
|
||||||
USD1_v0->update(sitl_model->rangefinder_range());
|
USD1_v0->update(sitl_model->rangefinder_range());
|
||||||
}
|
}
|
||||||
|
@ -37,6 +37,7 @@
|
|||||||
#include <SITL/SIM_RF_Lanbao.h>
|
#include <SITL/SIM_RF_Lanbao.h>
|
||||||
#include <SITL/SIM_RF_BLping.h>
|
#include <SITL/SIM_RF_BLping.h>
|
||||||
#include <SITL/SIM_RF_LeddarOne.h>
|
#include <SITL/SIM_RF_LeddarOne.h>
|
||||||
|
#include <SITL/SIM_RF_RDS02UF.h>
|
||||||
#include <SITL/SIM_RF_USD1_v0.h>
|
#include <SITL/SIM_RF_USD1_v0.h>
|
||||||
#include <SITL/SIM_RF_USD1_v1.h>
|
#include <SITL/SIM_RF_USD1_v1.h>
|
||||||
#include <SITL/SIM_RF_MaxsonarSerialLV.h>
|
#include <SITL/SIM_RF_MaxsonarSerialLV.h>
|
||||||
@ -226,6 +227,8 @@ private:
|
|||||||
SITL::RF_BLping *blping;
|
SITL::RF_BLping *blping;
|
||||||
// simulated LeddarOne rangefinder:
|
// simulated LeddarOne rangefinder:
|
||||||
SITL::RF_LeddarOne *leddarone;
|
SITL::RF_LeddarOne *leddarone;
|
||||||
|
// simulated RDS02UF rangefinder:
|
||||||
|
SITL::RF_RDS02UF *rds02uf;
|
||||||
// simulated USD1 v0 rangefinder:
|
// simulated USD1 v0 rangefinder:
|
||||||
SITL::RF_USD1_v0 *USD1_v0;
|
SITL::RF_USD1_v0 *USD1_v0;
|
||||||
// simulated USD1 v1 rangefinder:
|
// simulated USD1 v1 rangefinder:
|
||||||
|
Loading…
Reference in New Issue
Block a user