mirror of https://github.com/ArduPilot/ardupilot
HAL_Linux: change ring buffer to 300 entries
This commit is contained in:
parent
994b2597fd
commit
9b207d029d
|
@ -10,7 +10,9 @@
|
|||
#include <AP_HAL_Linux.h>
|
||||
|
||||
#define RCIN_PRUSS_SHAREDRAM_BASE 0x4a312000
|
||||
#define NUM_RING_ENTRIES 200
|
||||
// we use 300 ring buffer entries to guarantee that a full 25 byte
|
||||
// frame of 12 bits per byte
|
||||
#define NUM_RING_ENTRIES 300
|
||||
|
||||
class Linux::LinuxRCInput_PRU : public Linux::LinuxRCInput
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue