mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 23:18:29 -04:00
Replay: move AP_Airspeed to AP_Vehicle
This commit is contained in:
parent
5549c03e65
commit
2f7e07069f
@ -58,9 +58,11 @@ const AP_Param::Info ReplayVehicle::var_info[] = {
|
|||||||
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
|
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
|
||||||
GOBJECT(ahrs, "AHRS_", AP_AHRS),
|
GOBJECT(ahrs, "AHRS_", AP_AHRS),
|
||||||
|
|
||||||
|
#if AP_AIRSPEED_ENABLED
|
||||||
// @Group: ARSPD_
|
// @Group: ARSPD_
|
||||||
// @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp
|
// @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp
|
||||||
GOBJECT(airspeed, "ARSP_", AP_Airspeed),
|
GOBJECT(airspeed, "ARSP_", AP_Airspeed),
|
||||||
|
#endif
|
||||||
|
|
||||||
// @Group: EK2_
|
// @Group: EK2_
|
||||||
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
|
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
|
||||||
|
@ -46,7 +46,7 @@ public:
|
|||||||
virtual uint8_t get_mode() const override { return 0; }
|
virtual uint8_t get_mode() const override { return 0; }
|
||||||
|
|
||||||
AP_Vehicle::FixedWing aparm;
|
AP_Vehicle::FixedWing aparm;
|
||||||
AP_Airspeed airspeed;
|
|
||||||
AP_Int32 unused; // logging is magic for Replay; this is unused
|
AP_Int32 unused; // logging is magic for Replay; this is unused
|
||||||
struct LogStructure log_structure[256] = {
|
struct LogStructure log_structure[256] = {
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user