mirror of https://github.com/ArduPilot/ardupilot
Replay: fixed for AP_Vehicle usage
This commit is contained in:
parent
d8a58ebda4
commit
c0d9731dd4
|
@ -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();
|
||||
}
|
||||
}
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue