Browse Source

Replay: move AP_Airspeed to AP_Vehicle

gps-1.3.1
Josh Henderson 3 years ago committed by Andrew Tridgell
parent
commit
2f7e07069f
  1. 2
      Tools/Replay/Replay.cpp
  2. 2
      Tools/Replay/Replay.h

2
Tools/Replay/Replay.cpp

@ -58,9 +58,11 @@ const AP_Param::Info ReplayVehicle::var_info[] = { @@ -58,9 +58,11 @@ const AP_Param::Info ReplayVehicle::var_info[] = {
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
GOBJECT(ahrs, "AHRS_", AP_AHRS),
#if AP_AIRSPEED_ENABLED
// @Group: ARSPD_
// @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp
GOBJECT(airspeed, "ARSP_", AP_Airspeed),
#endif
// @Group: EK2_
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp

2
Tools/Replay/Replay.h

@ -46,7 +46,7 @@ public: @@ -46,7 +46,7 @@ public:
virtual uint8_t get_mode() const override { return 0; }
AP_Vehicle::FixedWing aparm;
AP_Airspeed airspeed;
AP_Int32 unused; // logging is magic for Replay; this is unused
struct LogStructure log_structure[256] = {
};

Loading…
Cancel
Save