mirror of https://github.com/ArduPilot/ardupilot
Tools: adjust Replay for new AP_Vehicle requirements
This commit is contained in:
parent
2401afd496
commit
bde97596eb
|
@ -102,10 +102,8 @@ void ReplayVehicle::load_parameters(void)
|
|||
AP_Param::set_default_by_name("LOG_FILE_BUFSIZE", 60);
|
||||
}
|
||||
|
||||
void ReplayVehicle::setup(void)
|
||||
void ReplayVehicle::init_ardupilot(void)
|
||||
{
|
||||
load_parameters();
|
||||
|
||||
// we pass an empty log structure, filling the structure in with
|
||||
// either the format present in the log (if we do not emit the
|
||||
// message as a product of Replay), or the format understood in
|
||||
|
|
|
@ -55,9 +55,11 @@ public:
|
|||
|
||||
ReplayVehicle() { unused = -1; }
|
||||
// HAL::Callbacks implementation.
|
||||
void setup() override;
|
||||
void loop() override;
|
||||
void load_parameters(void);
|
||||
void load_parameters(void) override;
|
||||
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
|
||||
uint8_t &task_count,
|
||||
uint32_t &log_bit) override { };
|
||||
|
||||
virtual bool set_mode(const uint8_t new_mode, const ModeReason reason) override { return true; }
|
||||
virtual uint8_t get_mode() const override { return 0; }
|
||||
|
@ -76,6 +78,10 @@ public:
|
|||
};
|
||||
AP_Logger logger{unused};
|
||||
|
||||
protected:
|
||||
|
||||
void init_ardupilot() override;
|
||||
|
||||
private:
|
||||
Parameters g;
|
||||
|
||||
|
|
Loading…
Reference in New Issue