mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tools: Replay: params always use set method
This commit is contained in:
parent
b3f09e5573
commit
2b69e69f7e
@ -31,7 +31,7 @@ class ReplayVehicle : public AP_Vehicle {
|
|||||||
public:
|
public:
|
||||||
friend class Replay;
|
friend class Replay;
|
||||||
|
|
||||||
ReplayVehicle() { unused = -1; }
|
ReplayVehicle() { unused.set(-1); }
|
||||||
// HAL::Callbacks implementation.
|
// HAL::Callbacks implementation.
|
||||||
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,
|
||||||
|
Loading…
Reference in New Issue
Block a user