AP_HAL_SITL: Use SITL, baro, INS and compass singletons
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
a4d8ed4b75
commit
cd5c59773b
@ -73,10 +73,10 @@ void SITL_State::_sitl_setup(const char *home_str)
|
||||
fprintf(stdout, "Starting SITL input\n");
|
||||
|
||||
// find the barometer object if it exists
|
||||
_sitl = (SITL::SITL *)AP_Param::find_object("SIM_");
|
||||
_barometer = (AP_Baro *)AP_Param::find_object("GND_");
|
||||
_ins = (AP_InertialSensor *)AP_Param::find_object("INS_");
|
||||
_compass = (Compass *)AP_Param::find_object("COMPASS_");
|
||||
_sitl = AP::sitl();
|
||||
_barometer = AP_Baro::get_instance();
|
||||
_ins = AP_InertialSensor::get_instance();
|
||||
_compass = Compass::get_singleton();
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
_terrain = reinterpret_cast<AP_Terrain *>(AP_Param::find_object("TERRAIN_"));
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user