From 8a3d3bed7263d5184f7f51fd3ef5d8c8318f8cc5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell <andrew@tridgell.net> Date: Mon, 5 Jan 2015 15:55:50 +1100 Subject: [PATCH] SITL: changes for new AP_Baro API --- libraries/AP_HAL_AVR_SITL/SITL_State.cpp | 4 ++-- libraries/AP_HAL_AVR_SITL/SITL_State.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_AVR_SITL/SITL_State.cpp b/libraries/AP_HAL_AVR_SITL/SITL_State.cpp index bf3ce7620..c0740b39a 100644 --- a/libraries/AP_HAL_AVR_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_AVR_SITL/SITL_State.cpp @@ -64,7 +64,7 @@ uint16_t SITL_State::voltage_pin_value; uint16_t SITL_State::current_pin_value; float SITL_State::_current; -AP_Baro_HIL *SITL_State::_barometer; +AP_Baro *SITL_State::_barometer; AP_InertialSensor *SITL_State::_ins; SITLScheduler *SITL_State::_scheduler; AP_Compass_HIL *SITL_State::_compass; @@ -213,7 +213,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_"); + _barometer = (AP_Baro *)AP_Param::find_object("GND_"); _ins = (AP_InertialSensor *)AP_Param::find_object("INS_"); _compass = (AP_Compass_HIL *)AP_Param::find_object("COMPASS_"); _terrain = (AP_Terrain *)AP_Param::find_object("TERRAIN_"); diff --git a/libraries/AP_HAL_AVR_SITL/SITL_State.h b/libraries/AP_HAL_AVR_SITL/SITL_State.h index 265cc0bec..3f8fcb4ef 100644 --- a/libraries/AP_HAL_AVR_SITL/SITL_State.h +++ b/libraries/AP_HAL_AVR_SITL/SITL_State.h @@ -125,7 +125,7 @@ private: static uint32_t _update_count; static bool _motors_on; - static AP_Baro_HIL *_barometer; + static AP_Baro *_barometer; static AP_InertialSensor *_ins; static SITLScheduler *_scheduler; static AP_Compass_HIL *_compass; -- GitLab