Browse Source

Replay: fixed build with new AP_Compass API

master
Andrew Tridgell 10 years ago
parent
commit
95a1ab0cab
  1. 2
      Tools/Replay/LogReader.cpp
  2. 4
      Tools/Replay/LogReader.h
  3. 2
      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 &_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, Compass &_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 &_baro, AP_Compass_HIL &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed, DataFlash_Class &_dataflash);
LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, AP_Baro &_baro, Compass &_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);
@ -45,7 +45,7 @@ private: @@ -45,7 +45,7 @@ private:
AP_AHRS &ahrs;
AP_InertialSensor &ins;
AP_Baro &baro;
AP_Compass_HIL &compass;
Compass &compass;
AP_GPS &gps;
AP_Airspeed &airspeed;
DataFlash_Class &dataflash;

2
Tools/Replay/Replay.pde

@ -69,7 +69,7 @@ static Parameters g; @@ -69,7 +69,7 @@ static Parameters g;
static AP_InertialSensor ins;
static AP_Baro barometer;
static AP_GPS gps;
static AP_Compass_HIL compass;
static Compass compass;
static AP_AHRS_NavEKF ahrs(ins, barometer, gps);
static AP_InertialNav_NavEKF inertial_nav(ahrs);
static AP_Vehicle::FixedWing aparm;

Loading…
Cancel
Save