mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: fixed copying of filter objects
This commit is contained in:
parent
0ecc02c53a
commit
f150c312a6
@ -264,8 +264,8 @@ private:
|
||||
|
||||
// cruise throttle and speed learning
|
||||
typedef struct {
|
||||
LowPassFilterFloat speed_filt = LowPassFilterFloat(2.0f);
|
||||
LowPassFilterFloat throttle_filt = LowPassFilterFloat(2.0f);
|
||||
LowPassFilterFloat speed_filt{2.0f};
|
||||
LowPassFilterFloat throttle_filt{2.0f};
|
||||
uint32_t learn_start_ms;
|
||||
uint32_t log_count;
|
||||
} cruise_learn_t;
|
||||
|
Loading…
Reference in New Issue
Block a user