mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Replay: let AP_Vehicle handle loop()
This commit is contained in:
parent
a523bb4b68
commit
b8087c3e84
@ -130,10 +130,6 @@ void ReplayVehicle::init_ardupilot(void)
|
|||||||
ins.set_hil_mode();
|
ins.set_hil_mode();
|
||||||
}
|
}
|
||||||
|
|
||||||
void ReplayVehicle::loop()
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
Replay replay(replayvehicle);
|
Replay replay(replayvehicle);
|
||||||
|
|
||||||
void Replay::usage(void)
|
void Replay::usage(void)
|
||||||
|
@ -55,7 +55,6 @@ public:
|
|||||||
|
|
||||||
ReplayVehicle() { unused = -1; }
|
ReplayVehicle() { unused = -1; }
|
||||||
// HAL::Callbacks implementation.
|
// HAL::Callbacks implementation.
|
||||||
void loop() override;
|
|
||||||
void load_parameters(void) override;
|
void load_parameters(void) override;
|
||||||
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
|
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
|
||||||
uint8_t &task_count,
|
uint8_t &task_count,
|
||||||
|
Loading…
Reference in New Issue
Block a user