Internal Errors 0x2000000 with WheelEncoder -- ArduRover 4.5.2

I can’t see rpm value large then 0 in MP, even the motor is spining.

Currently, Servo & ENC settings (H743 PWM3/4/5/6 are numbered 52/53/54/55)

When moto spins, I see following "ISR flood"message.

My encoder 1024 PPR with 1: 60 reduction ratio, so I got 1024 x 60 = 61440 CPR
In reality, it will trigger 10000 counts/100ms.

Anyone can help?

24/5/21 6:03:39 : Retrying pin 53 after ISR flood
24/5/21 6:03:39 : Retrying pin 52 after ISR flood
24/5/21 6:03:29 : Throttle disarmed
24/5/21 6:03:25 : Internal Errors 0x2000000
24/5/21 6:03:25 : ISR flood on pin 53
24/5/21 6:03:25 : ISR flood on pin 52
24/5/21 6:03:22 : Throttle armed
24/5/21 6:03:22 : Warning: Arming Checks Disabled
24/5/21 6:03:19 : ELRS: Link rate 150Hz, Telemetry rate 69Hz
24/5/21 6:03:16 : AHRS: EKF3 active
24/5/21 6:03:16 : EKF3 IMU1 tilt alignment complete
24/5/21 6:03:16 : EKF3 IMU0 tilt alignment complete
24/5/21 6:03:15 : EKF3 IMU1 initialised
24/5/21 6:03:15 : EKF3 IMU0 initialised
24/5/21 6:03:15 : ELRS: RSSI now displays normally
24/5/21 6:03:15 : ELRS: Link rate 150Hz, Telemetry rate 149Hz
24/5/21 6:03:13 : RCInput: decoding CRSF(3)
24/5/21 6:03:13 : RCOut: PWM:1-2 PWM:7-13
24/5/21 6:03:13 : Aocoda-RC-H743Dual 0036002A 3031510A 39373436
24/5/21 6:03:13 : ChibiOS: 6a85082c
24/5/21 6:03:13 : ArduRover V4.5.2 (5d9c84ca)
24/5/21 6:03:12 : RCOut: PWM:1-2 PWM:7-13
24/5/21 6:03:12 : AHRS: DCM active
24/5/21 6:03:12 : ArduPilot Ready
24/5/21 6:03:12 : RCOut: Initialising
24/5/21 6:03:12 : Aocoda-RC-H743Dual 0036002A 3031510A 39373436
24/5/21 6:03:12 : ChibiOS: 6a85082c
24/5/21 6:03:12 : ArduRover V4.5.2 (5d9c84ca)
24/5/21 6:03:12 : RCOut: Initialising
24/5/21 6:03:12 : Aocoda-RC-H743Dual 0036002A 3031510A 39373436
24/5/21 6:03:12 : ChibiOS: 6a85082c
24/5/21 6:03:12 : ArduRover V4.5.2 (5d9c84ca)
24/5/21 6:03:11 : Beginning INS calibration. Do not move vehicle
24/5/21 6:03:11 : Barometer 1 calibration complete

Given from the liked code, there’s an upper limit of 100,000 counts per second.

If your encoder produces 61440 CPR, that limits your wheel’s rotation to a maximum of 1.6 revolutions per second.

Does the issue occur at <1.6 revolutions per second?

I can’t control the throttle exactly.

But it feels that way:
a) when low throttle(very very low, just one motor spin, other even not spin at all), then there is no such warning.
b) With motor spin faster, then flood warning comes in.

BTW, what kind of wheelencorder are you using? is the CPR that high like mine? Any concerns on this flood?

EDIT: I never saw flood warnings on pin 54/55? The most important thing is there is RPM :frowning:

I’m using: Pololu - 20.4:1 Metal Gearmotor 25Dx65L mm HP 12V with 48 CPR Encoder. 48CPR and 20.4:1 ratio. So WENCn_CPR = 979

61440 CPR is extremely high. Judging by your error messages, likely too high for ArduPilot.

Now I got confirmed info from AKM manufacturer.

My configurations(which I ordered):

  • max 300RPM
  • reduction ratio 1:30
  • quadrature encorder
  • 1024 PPR
  • 75mm rubber tire

CPR = 1024 x 30 x 4 = 122,880 which is 122,880 pulse wheels rotate once.
Note:This formula was told to me by the manufacturer.

Current CPU is low 4%, I just try 60000 quota instead of 10000, then warning is gone (Maybe not full speed), CPU fron 4% to 30%.

But I didn’t see RPM value (Or I have look wrong rpm data?). Is there anything I should take care of?

That’s the correct place. Post all your WENC* params

I have set WENC_CPR 1024/3200/ etc.

Step 1: set WENC_CPR/ WENC2_CPR
Step 2: reboot flight controller
Step 3: throttle up and down
Step 4: check rpm1/rpm2

The above configuration did affect rpm1/rmp2, always 0. (Running my custom build quota 60000, instead of 10000)

EDIT:

WENC*_CPR can’t be set to 122880, it will overflow. maximum is 32767. And I still got rpm1/rpm2 zero.

Sorry - wrong information here. It’s not shown in the status window. You’ll need to go CTRL+F → MAVLink Inspector and look for the WHEEL_DISTANCE messages.

Only the first value of distance changes (and time). Is that OK?

EDIT: It seems not accurate. Is there any calibration can adjust the CPR issue?
Normally, it should something like below calculation.

But CPR is an INT16, can’t be set more than 32,768.

How about below settings?

Give it a go and see if it gives you realistic numbers

1 Like

(Tape measure)3500mm v.s. (Readings from QGC MAVLink Inspector)3654.79

Well, not that accurate, but it’s close, anyway it’s rubber tier.

@stephendade As there are two encoders, I didn’t see two lines of distance. Is there any way to find out?

You can experiment with slight changes to the wheel radius (WENCn_RADIUS) to get a better accuracy. For my rover, I increased the radius from 6cm to 6.1cm and got better results. As you say, the wheel radius can vary a bit depending on manufacturing tolerances and compression from the vehicle’s weight.

I think the param for your 2nd encoder are not quite right. Try WENC2_PINA = 57 and WENC2_PINB = 56

Yes, you are right. You’re so meticulous, which prompts me to update the wiki as soon as possible. Thank you!

Hmmm… New progress, new problem! :)