Skip to content
Snippets Groups Projects
Commit 488714cc authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

Replay: updates for new AP_Baro API

parent c151f246
No related branches found
No related tags found
No related merge requests found
...@@ -18,7 +18,7 @@ ...@@ -18,7 +18,7 @@
extern const AP_HAL::HAL& hal; 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), vehicle(VEHICLE_UNKNOWN),
fd(-1), fd(-1),
ahrs(_ahrs), ahrs(_ahrs),
......
...@@ -20,7 +20,7 @@ enum log_messages { ...@@ -20,7 +20,7 @@ enum log_messages {
class LogReader class LogReader
{ {
public: 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 open_log(const char *logfile);
bool update(uint8_t &type); bool update(uint8_t &type);
bool wait_type(uint8_t type); bool wait_type(uint8_t type);
...@@ -44,7 +44,7 @@ private: ...@@ -44,7 +44,7 @@ private:
int fd; int fd;
AP_AHRS &ahrs; AP_AHRS &ahrs;
AP_InertialSensor &ins; AP_InertialSensor &ins;
AP_Baro_HIL &baro; AP_Baro &baro;
AP_Compass_HIL &compass; AP_Compass_HIL &compass;
AP_GPS &gps; AP_GPS &gps;
AP_Airspeed &airspeed; AP_Airspeed &airspeed;
......
...@@ -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 Parameters g;
static AP_InertialSensor ins; static AP_InertialSensor ins;
static AP_Baro_HIL barometer; static AP_Baro barometer;
static AP_GPS gps; static AP_GPS gps;
static AP_Compass_HIL compass; static AP_Compass_HIL compass;
static AP_AHRS_NavEKF ahrs(ins, barometer, gps); static AP_AHRS_NavEKF ahrs(ins, barometer, gps);
...@@ -213,7 +213,7 @@ void setup() ...@@ -213,7 +213,7 @@ void setup()
barometer.init(); barometer.init();
barometer.setHIL(0); barometer.setHIL(0);
barometer.read(); barometer.update();
compass.init(); compass.init();
inertial_nav.init(); inertial_nav.init();
ins.set_hil_mode(); 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) { } else if (type == LOG_PLANE_AIRSPEED_MSG && LogReader.vehicle == LogReader::VEHICLE_PLANE) {
ahrs.set_airspeed(&airspeed); ahrs.set_airspeed(&airspeed);
} else if (type == LOG_BARO_MSG) { } else if (type == LOG_BARO_MSG) {
barometer.read(); barometer.update();
if (!done_baro_init) { if (!done_baro_init) {
done_baro_init = true; done_baro_init = true;
::printf("Barometer initialised\n"); ::printf("Barometer initialised\n");
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment