mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL_SITL: rename uLanding simulation to USD1
This commit is contained in:
parent
4f2bec72b6
commit
8192661042
@ -271,18 +271,18 @@ int SITL_State::sim_fd(const char *name, const char *arg)
|
|||||||
}
|
}
|
||||||
leddarone = new SITL::RF_LeddarOne();
|
leddarone = new SITL::RF_LeddarOne();
|
||||||
return leddarone->fd();
|
return leddarone->fd();
|
||||||
} else if (streq(name, "ulanding_v0")) {
|
} else if (streq(name, "USD1_v0")) {
|
||||||
if (ulanding_v0 != nullptr) {
|
if (USD1_v0 != nullptr) {
|
||||||
AP_HAL::panic("Only one ulanding_v0 at a time");
|
AP_HAL::panic("Only one USD1_v0 at a time");
|
||||||
}
|
}
|
||||||
ulanding_v0 = new SITL::RF_uLanding_v0();
|
USD1_v0 = new SITL::RF_USD1_v0();
|
||||||
return ulanding_v0->fd();
|
return USD1_v0->fd();
|
||||||
} else if (streq(name, "ulanding_v1")) {
|
} else if (streq(name, "USD1_v1")) {
|
||||||
if (ulanding_v1 != nullptr) {
|
if (USD1_v1 != nullptr) {
|
||||||
AP_HAL::panic("Only one ulanding_v1 at a time");
|
AP_HAL::panic("Only one USD1_v1 at a time");
|
||||||
}
|
}
|
||||||
ulanding_v1 = new SITL::RF_uLanding_v1();
|
USD1_v1 = new SITL::RF_USD1_v1();
|
||||||
return ulanding_v1->fd();
|
return USD1_v1->fd();
|
||||||
} else if (streq(name, "maxsonarseriallv")) {
|
} else if (streq(name, "maxsonarseriallv")) {
|
||||||
if (maxsonarseriallv != nullptr) {
|
if (maxsonarseriallv != nullptr) {
|
||||||
AP_HAL::panic("Only one maxsonarseriallv at a time");
|
AP_HAL::panic("Only one maxsonarseriallv at a time");
|
||||||
@ -453,16 +453,16 @@ int SITL_State::sim_fd_write(const char *name)
|
|||||||
AP_HAL::panic("No leddarone created");
|
AP_HAL::panic("No leddarone created");
|
||||||
}
|
}
|
||||||
return leddarone->write_fd();
|
return leddarone->write_fd();
|
||||||
} else if (streq(name, "ulanding_v0")) {
|
} else if (streq(name, "USD1_v0")) {
|
||||||
if (ulanding_v0 == nullptr) {
|
if (USD1_v0 == nullptr) {
|
||||||
AP_HAL::panic("No ulanding_v0 created");
|
AP_HAL::panic("No USD1_v0 created");
|
||||||
}
|
}
|
||||||
return ulanding_v0->write_fd();
|
return USD1_v0->write_fd();
|
||||||
} else if (streq(name, "ulanding_v1")) {
|
} else if (streq(name, "USD1_v1")) {
|
||||||
if (ulanding_v1 == nullptr) {
|
if (USD1_v1 == nullptr) {
|
||||||
AP_HAL::panic("No ulanding_v1 created");
|
AP_HAL::panic("No USD1_v1 created");
|
||||||
}
|
}
|
||||||
return ulanding_v1->write_fd();
|
return USD1_v1->write_fd();
|
||||||
} else if (streq(name, "maxsonarseriallv")) {
|
} else if (streq(name, "maxsonarseriallv")) {
|
||||||
if (maxsonarseriallv == nullptr) {
|
if (maxsonarseriallv == nullptr) {
|
||||||
AP_HAL::panic("No maxsonarseriallv created");
|
AP_HAL::panic("No maxsonarseriallv created");
|
||||||
@ -717,11 +717,11 @@ 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 (ulanding_v0 != nullptr) {
|
if (USD1_v0 != nullptr) {
|
||||||
ulanding_v0->update(sitl_model->rangefinder_range());
|
USD1_v0->update(sitl_model->rangefinder_range());
|
||||||
}
|
}
|
||||||
if (ulanding_v1 != nullptr) {
|
if (USD1_v1 != nullptr) {
|
||||||
ulanding_v1->update(sitl_model->rangefinder_range());
|
USD1_v1->update(sitl_model->rangefinder_range());
|
||||||
}
|
}
|
||||||
if (maxsonarseriallv != nullptr) {
|
if (maxsonarseriallv != nullptr) {
|
||||||
maxsonarseriallv->update(sitl_model->rangefinder_range());
|
maxsonarseriallv->update(sitl_model->rangefinder_range());
|
||||||
|
@ -36,8 +36,8 @@
|
|||||||
#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_uLanding_v0.h>
|
#include <SITL/SIM_RF_USD1_v0.h>
|
||||||
#include <SITL/SIM_RF_uLanding_v1.h>
|
#include <SITL/SIM_RF_USD1_v1.h>
|
||||||
#include <SITL/SIM_RF_MaxsonarSerialLV.h>
|
#include <SITL/SIM_RF_MaxsonarSerialLV.h>
|
||||||
#include <SITL/SIM_RF_Wasp.h>
|
#include <SITL/SIM_RF_Wasp.h>
|
||||||
#include <SITL/SIM_RF_NMEA.h>
|
#include <SITL/SIM_RF_NMEA.h>
|
||||||
@ -239,10 +239,10 @@ private:
|
|||||||
SITL::RF_BLping *blping;
|
SITL::RF_BLping *blping;
|
||||||
// simulated LeddarOne rangefinder:
|
// simulated LeddarOne rangefinder:
|
||||||
SITL::RF_LeddarOne *leddarone;
|
SITL::RF_LeddarOne *leddarone;
|
||||||
// simulated uLanding v0 rangefinder:
|
// simulated USD1 v0 rangefinder:
|
||||||
SITL::RF_uLanding_v0 *ulanding_v0;
|
SITL::RF_USD1_v0 *USD1_v0;
|
||||||
// simulated uLanding v1 rangefinder:
|
// simulated USD1 v1 rangefinder:
|
||||||
SITL::RF_uLanding_v1 *ulanding_v1;
|
SITL::RF_USD1_v1 *USD1_v1;
|
||||||
// simulated MaxsonarSerialLV rangefinder:
|
// simulated MaxsonarSerialLV rangefinder:
|
||||||
SITL::RF_MaxsonarSerialLV *maxsonarseriallv;
|
SITL::RF_MaxsonarSerialLV *maxsonarseriallv;
|
||||||
// simulated Wasp rangefinder:
|
// simulated Wasp rangefinder:
|
||||||
|
Loading…
Reference in New Issue
Block a user