Browse Source

Rover: fixed copying of filter objects

c415-sdk
Andrew Tridgell 4 years ago
parent
commit
f150c312a6
  1. 4
      Rover/Rover.h

4
Rover/Rover.h

@ -264,8 +264,8 @@ private: @@ -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…
Cancel
Save