Replay: fixed for AP_Vehicle usage

This commit is contained in:
Andrew Tridgell 2019-12-30 09:36:34 +11:00
parent d8a58ebda4
commit c0d9731dd4
2 changed files with 6 additions and 9 deletions

View File

@ -183,6 +183,10 @@ void LogReader::initialise_fmt_map()
continue;
}
::fprintf(stderr, "Failed to find apparently-generated-name (%s) in COMMON_LOG_STRUCTURES\n", *name);
if (strncmp(*name, "NK", 2)==0 || strncmp(*name, "XK", 2) == 0) {
// cope with older logs
continue;
}
abort();
}
}

View File

@ -51,6 +51,8 @@
class ReplayVehicle : public AP_Vehicle {
public:
friend class Replay;
ReplayVehicle() { unused = -1; }
// HAL::Callbacks implementation.
void setup() override;
@ -59,15 +61,6 @@ public:
virtual bool set_mode(const uint8_t new_mode, const ModeReason reason) override { return true; }
AP_InertialSensor ins;
AP_Baro barometer;
AP_GPS gps;
Compass compass;
AP_SerialManager serial_manager;
RangeFinder rng;
NavEKF2 EKF2{&ahrs};
NavEKF3 EKF3{&ahrs};
AP_AHRS_NavEKF ahrs{EKF2, EKF3};
AP_Vehicle::FixedWing aparm;
AP_Airspeed airspeed;
AP_Int32 unused; // logging is magic for Replay; this is unused