diff --git a/Tools/Replay/LogReader.cpp b/Tools/Replay/LogReader.cpp index 33bf112511de84501164f925ef93b7007c3d714c..53d4db51a1b58886378275af426ac7452788f07e 100644 --- a/Tools/Replay/LogReader.cpp +++ b/Tools/Replay/LogReader.cpp @@ -18,7 +18,7 @@ extern const AP_HAL::HAL& hal; -LogReader::LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, AP_Baro_HIL &_baro, AP_Compass_HIL &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed, DataFlash_Class &_dataflash) : +LogReader::LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, AP_Baro &_baro, AP_Compass_HIL &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed, DataFlash_Class &_dataflash) : vehicle(VEHICLE_UNKNOWN), fd(-1), ahrs(_ahrs), diff --git a/Tools/Replay/LogReader.h b/Tools/Replay/LogReader.h index 7359e240c4a0615561ddce363304f86fbfe8691f..f554ed5066bdbb2d608d7a9a24f8fe228dcf1c55 100644 --- a/Tools/Replay/LogReader.h +++ b/Tools/Replay/LogReader.h @@ -20,7 +20,7 @@ enum log_messages { class LogReader { public: - LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, AP_Baro_HIL &_baro, AP_Compass_HIL &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed, DataFlash_Class &_dataflash); + LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, AP_Baro &_baro, AP_Compass_HIL &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed, DataFlash_Class &_dataflash); bool open_log(const char *logfile); bool update(uint8_t &type); bool wait_type(uint8_t type); @@ -44,7 +44,7 @@ private: int fd; AP_AHRS &ahrs; AP_InertialSensor &ins; - AP_Baro_HIL &baro; + AP_Baro &baro; AP_Compass_HIL &compass; AP_GPS &gps; AP_Airspeed &airspeed; diff --git a/Tools/Replay/Replay.pde b/Tools/Replay/Replay.pde index 70c6c3f587466f443254cbf88082e80a3f41757f..a63aed7e94534474f72165c81e03c1cd826bc144 100644 --- a/Tools/Replay/Replay.pde +++ b/Tools/Replay/Replay.pde @@ -67,7 +67,7 @@ const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; static Parameters g; static AP_InertialSensor ins; -static AP_Baro_HIL barometer; +static AP_Baro barometer; static AP_GPS gps; static AP_Compass_HIL compass; static AP_AHRS_NavEKF ahrs(ins, barometer, gps); @@ -213,7 +213,7 @@ void setup() barometer.init(); barometer.setHIL(0); - barometer.read(); + barometer.update(); compass.init(); inertial_nav.init(); ins.set_hil_mode(); @@ -325,7 +325,7 @@ static void read_sensors(uint8_t type) } else if (type == LOG_PLANE_AIRSPEED_MSG && LogReader.vehicle == LogReader::VEHICLE_PLANE) { ahrs.set_airspeed(&airspeed); } else if (type == LOG_BARO_MSG) { - barometer.read(); + barometer.update(); if (!done_baro_init) { done_baro_init = true; ::printf("Barometer initialised\n");