mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
libraries: fixes for AP_Baro_HIL
This commit is contained in:
parent
2d089174cd
commit
811c2ccc11
@ -47,7 +47,7 @@ AP_GPS_Auto g_gps_driver(&g_gps);
|
||||
AP_AHRS_DCM ahrs(&ins, g_gps);
|
||||
//AP_AHRS_MPU6000 ahrs(&ins, g_gps); // only works with APM2
|
||||
|
||||
AP_Baro_BMP085_HIL barometer;
|
||||
AP_Baro_HIL barometer;
|
||||
|
||||
|
||||
#define HIGH 1
|
||||
|
@ -33,7 +33,7 @@ uint32_t SITL_State::_update_count;
|
||||
bool SITL_State::_motors_on;
|
||||
uint16_t SITL_State::airspeed_pin_value;
|
||||
|
||||
AP_Baro_BMP085_HIL *SITL_State::_barometer;
|
||||
AP_Baro_HIL *SITL_State::_barometer;
|
||||
AP_InertialSensor_Stub *SITL_State::_ins;
|
||||
SITLScheduler *SITL_State::_scheduler;
|
||||
AP_Compass_HIL *SITL_State::_compass;
|
||||
@ -133,7 +133,7 @@ void SITL_State::_sitl_setup(void)
|
||||
|
||||
// find the barometer object if it exists
|
||||
_sitl = (SITL *)AP_Param::find_object("SIM_");
|
||||
_barometer = (AP_Baro_BMP085_HIL *)AP_Param::find_object("GND_");
|
||||
_barometer = (AP_Baro_HIL *)AP_Param::find_object("GND_");
|
||||
_ins = (AP_InertialSensor_Stub *)AP_Param::find_object("INS_");
|
||||
_compass = (AP_Compass_HIL *)AP_Param::find_object("COMPASS_");
|
||||
|
||||
|
@ -103,7 +103,7 @@ private:
|
||||
static uint32_t _update_count;
|
||||
static bool _motors_on;
|
||||
|
||||
static AP_Baro_BMP085_HIL *_barometer;
|
||||
static AP_Baro_HIL *_barometer;
|
||||
static AP_InertialSensor_Stub *_ins;
|
||||
static SITLScheduler *_scheduler;
|
||||
static AP_Compass_HIL *_compass;
|
||||
|
Loading…
Reference in New Issue
Block a user