Browse Source

SITL: increase Wasp reading frequency

The driver requires a reading each time it is called (20Hz)
c415-sdk
Peter Barker 5 years ago committed by Peter Barker
parent
commit
d332118b05
  1. 4
      libraries/SITL/SIM_RF_Wasp.h

4
libraries/SITL/SIM_RF_Wasp.h

@ -40,6 +40,10 @@ public: @@ -40,6 +40,10 @@ public:
uint32_t packet_for_alt(uint16_t alt_cm, uint8_t *buffer, uint8_t buflen) override;
// 20Hz; if Wasp driver doesn't get a reading each time its update
// is called it goes NoData
uint16_t reading_interval_ms() const override { return 50; }
private:
void check_configuration();

Loading…
Cancel
Save