mirror of https://github.com/ArduPilot/ardupilot
AP_Proximity: Use SITL singleton
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
653784479e
commit
50613c3800
|
@ -30,9 +30,9 @@ extern const AP_HAL::HAL& hal;
|
||||||
*/
|
*/
|
||||||
AP_Proximity_SITL::AP_Proximity_SITL(AP_Proximity &_frontend,
|
AP_Proximity_SITL::AP_Proximity_SITL(AP_Proximity &_frontend,
|
||||||
AP_Proximity::Proximity_State &_state):
|
AP_Proximity::Proximity_State &_state):
|
||||||
AP_Proximity_Backend(_frontend, _state)
|
AP_Proximity_Backend(_frontend, _state),
|
||||||
|
sitl(AP::sitl())
|
||||||
{
|
{
|
||||||
sitl = (SITL::SITL *)AP_Param::find_object("SIM_");
|
|
||||||
ap_var_type ptype;
|
ap_var_type ptype;
|
||||||
fence_count = (AP_Int8 *)AP_Param::find("FENCE_TOTAL", &ptype);
|
fence_count = (AP_Int8 *)AP_Param::find("FENCE_TOTAL", &ptype);
|
||||||
if (fence_count == nullptr || ptype != AP_PARAM_INT8) {
|
if (fence_count == nullptr || ptype != AP_PARAM_INT8) {
|
||||||
|
|
Loading…
Reference in New Issue