Browse Source

Replay: updates for new AP_Baro API

master
Andrew Tridgell 10 years ago
parent
commit
488714ccba
  1. 2
      Tools/Replay/LogReader.cpp
  2. 4
      Tools/Replay/LogReader.h
  3. 6
      Tools/Replay/Replay.pde

2
Tools/Replay/LogReader.cpp

@ -18,7 +18,7 @@ @@ -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),

4
Tools/Replay/LogReader.h

@ -20,7 +20,7 @@ enum log_messages { @@ -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: @@ -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;

6
Tools/Replay/Replay.pde

@ -67,7 +67,7 @@ const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; @@ -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() @@ -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) @@ -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");

Loading…
Cancel
Save