SITL: update for new AP_InertialSensor API
This commit is contained in:
parent
ec11417705
commit
0ce5c99c26
@ -65,7 +65,7 @@ uint16_t SITL_State::current_pin_value;
|
||||
float SITL_State::_current;
|
||||
|
||||
AP_Baro_HIL *SITL_State::_barometer;
|
||||
AP_InertialSensor_HIL *SITL_State::_ins;
|
||||
AP_InertialSensor *SITL_State::_ins;
|
||||
SITLScheduler *SITL_State::_scheduler;
|
||||
AP_Compass_HIL *SITL_State::_compass;
|
||||
|
||||
@ -212,7 +212,7 @@ void SITL_State::_sitl_setup(void)
|
||||
// find the barometer object if it exists
|
||||
_sitl = (SITL *)AP_Param::find_object("SIM_");
|
||||
_barometer = (AP_Baro_HIL *)AP_Param::find_object("GND_");
|
||||
_ins = (AP_InertialSensor_HIL *)AP_Param::find_object("INS_");
|
||||
_ins = (AP_InertialSensor *)AP_Param::find_object("INS_");
|
||||
_compass = (AP_Compass_HIL *)AP_Param::find_object("COMPASS_");
|
||||
|
||||
if (_sitl != NULL) {
|
||||
|
@ -121,7 +121,7 @@ private:
|
||||
static bool _motors_on;
|
||||
|
||||
static AP_Baro_HIL *_barometer;
|
||||
static AP_InertialSensor_HIL *_ins;
|
||||
static AP_InertialSensor *_ins;
|
||||
static SITLScheduler *_scheduler;
|
||||
static AP_Compass_HIL *_compass;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user