mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-19 07:08:29 -04:00
AP_HAL_SITL: add LD06 simulator
This commit is contained in:
parent
3e2428334b
commit
c1ce04a0ce
@ -136,6 +136,14 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
|
||||
crsf = NEW_NOTHROW SITL::CRSF();
|
||||
return crsf;
|
||||
#endif
|
||||
#if AP_SIM_PS_LD06_ENABLED
|
||||
} else if (streq(name, "ld06")) {
|
||||
if (ld06 != nullptr) {
|
||||
AP_HAL::panic("Only one ld06 at a time");
|
||||
}
|
||||
ld06 = NEW_NOTHROW SITL::PS_LD06();
|
||||
return ld06;
|
||||
#endif // AP_SIM_PS_LD06_ENABLED
|
||||
#if HAL_SIM_PS_RPLIDARA2_ENABLED
|
||||
} else if (streq(name, "rplidara2")) {
|
||||
if (rplidara2 != nullptr) {
|
||||
@ -314,6 +322,12 @@ void SITL_State_Common::sim_update(void)
|
||||
}
|
||||
#endif
|
||||
|
||||
#if AP_SIM_PS_LD06_ENABLED
|
||||
if (ld06 != nullptr) {
|
||||
ld06->update(sitl_model->get_location());
|
||||
}
|
||||
#endif // AP_SIM_PS_LD06_ENABLED
|
||||
|
||||
#if HAL_SIM_PS_RPLIDARA2_ENABLED
|
||||
if (rplidara2 != nullptr) {
|
||||
rplidara2->update(sitl_model->get_location());
|
||||
|
@ -26,6 +26,7 @@
|
||||
#include <SITL/SIM_CRSF.h>
|
||||
// #include <SITL/SIM_Frsky_SPort.h>
|
||||
// #include <SITL/SIM_Frsky_SPortPassthrough.h>
|
||||
#include <SITL/SIM_PS_LD06.h>
|
||||
#include <SITL/SIM_PS_RPLidarA2.h>
|
||||
#include <SITL/SIM_PS_RPLidarA1.h>
|
||||
#include <SITL/SIM_PS_TeraRangerTower.h>
|
||||
@ -115,6 +116,11 @@ public:
|
||||
// SITL::Frsky_SPort *frsky_sport;
|
||||
// SITL::Frsky_SPortPassthrough *frsky_sportpassthrough;
|
||||
|
||||
#if AP_SIM_PS_LD06_ENABLED
|
||||
// simulated LD06:
|
||||
SITL::PS_LD06 *ld06;
|
||||
#endif // AP_SIM_PS_LD06_ENABLED
|
||||
|
||||
#if HAL_SIM_PS_RPLIDARA2_ENABLED
|
||||
// simulated RPLidarA2:
|
||||
SITL::PS_RPLidarA2 *rplidara2;
|
||||
|
Loading…
Reference in New Issue
Block a user