mirror of https://github.com/ArduPilot/ardupilot
Replay: enable LOG_REPLAY in replay
This commit is contained in:
parent
ea508f1b80
commit
248ce2e0e6
|
@ -15,7 +15,8 @@ public:
|
|||
k_param_airspeed,
|
||||
k_param_NavEKF,
|
||||
k_param_NavEKF2,
|
||||
k_param_compass
|
||||
k_param_compass,
|
||||
k_param_dataflash
|
||||
};
|
||||
AP_Int8 dummy;
|
||||
};
|
||||
|
|
|
@ -139,6 +139,10 @@ const AP_Param::Info ReplayVehicle::var_info[] = {
|
|||
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
|
||||
GOBJECT(compass, "COMPASS_", Compass),
|
||||
|
||||
// @Group: LOG
|
||||
// @Path: ../libraries/DataFlash/DataFlash.cpp
|
||||
GOBJECT(dataflash, "LOG", DataFlash_Class),
|
||||
|
||||
AP_VAREND
|
||||
};
|
||||
|
||||
|
@ -151,6 +155,7 @@ void ReplayVehicle::load_parameters(void)
|
|||
}
|
||||
AP_Param::set_default_by_name("EKF_ENABLE", 1);
|
||||
AP_Param::set_default_by_name("EK2_ENABLE", 1);
|
||||
AP_Param::set_default_by_name("LOG_REPLAY", 1);
|
||||
AP_Param::set_default_by_name("AHRS_EKF_TYPE", 2);
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue