Zubax error count deciphering

Hi everyone,
After conducting some flight tests with a hexarotor equipped with 6 MyxaB controllers, we investigated the Ardupilot log and found some of the Myxas to have a rising error count throughout the flight.
How can I investigate what were the actual errors that disturbed the ESC?
Is “Ecnt” in the Ardupilot log simply a count of the number of errors/warnings that were encountered by the Myxa?

I am not sure about the data handling and representations adopted by ArduPilot, but the UAVCAN field error_count of the ESC status message represents the number of times the rotor was stalled since the last requested spinup.

For example, once you commanded the motor to stop, the error counter will be cleared (zeroed). Once you commanded the motor to start (by sending any non-zero setpoint), the error counter will be reflecting the number of times the rotor was forcibly stalled either by excessive load torque or by a misbehaving control loop due to a tuning issue.

I recommend you to consult with the ArduPilot community to find out the meaning of the metric you’re inquiring about.

Thanks for the reply Pavel.
The Ardupilot code does nothing special but only logs the error_count field from the esc.status messages as they come in.

We are operating at relatively low RPMs (~1500) and we see that some of the Myxas’ error count start rising while in the air (with ESC 4 in particular). When the Ecount reaches 100 the ESC is shut down.


I would have guessed that when the RPM of the motor drops - the Myxa is having trouble accelerating it back again, the current peaks and an error is thrown, but I can’t see good correlation to that.

What could be the reason of this behavior?
What would be the recommended parameters to look at?
Does the shutdown of the ESC after 100 errors something that is programmed into it? Can it be changed?

Our motors are connected to a gearbox. Should we perform the motor autotune procedure while connected to the gearbox or with the motor fully disconnected? Is it important to perform each arm’s autotune separately or copying a single arm’s parameters to all other arms (having the same motor+gearbox combination of-course) close enough?

Thanks for the help.

Can you reproduce this behavior on the ground? Can you please dump the configuration parameters and share the file with us? Are you using the default settings of the motor control loop (aside from the motor parameters) or have you retuned the drive? Thanks.

Irrespective of the cause, you can control this behavior by setting the error limit register ctl.num_attempts, up to effectively disabling this behavior by raising the limit to the maximum, which is 10 million errors.

Thanks Pavel.
Here are the specific controller’s parameters:

uavcan.node_id 53
uavcan.esc_index 3
uavcan.esc_ttl 0.5
uavcan.esc_sint 0.050000001
uavcan.esc_sintp 0.5
uavcan.esc_rcm 2
uavcan.esc_revrs FALSE
rcpwm.ttl 0.300000012
rcpwm.ctl_mode 2
rcpwm.reverse FALSE
ctl.spinup_durat 1.5
ctl.num_attempts 100
ctl.vm_cci_comp FALSE
ctl.vm_oversatur FALSE
ctl.pwron_slftst FALSE
ctl.hard_stop FALSE
ctl.vm_pppwm_thr 0.949999988
ctl.field_weaken FALSE
ctl.fw_v_boost 1.200000048
m.num_poles 28
m.max_current 28
m.max_id_current 0
m.min_current 0.100000001
m.spup_curr_begn 2
m.spup_curr_end 0.25
m.flux_linkage 0.001807593
m.resistance 0.056620944
m.induct_direct 2.47E-05
m.induct_quadrat 2.47E-05
m.min_eangvel 400
m.max_eangvel 17500
m.current_ramp 100
m.voltage_ramp 15
m.eangvel_accel 6000
m.eangvel_decel 5000
m.eangvel_ctl_kp 0.003
m.eangvel_ctl_ki 0.005
m.eangvel_ctl_kd 1.00E-06
m.current_ctl_bw 0.050000001
m.bemf_ctl_kp 9.600000381
m.bemf_ctl_ki 0.949999988
m.fw_evel_hyst 100
mid.phi.curr_mul 0.300000012
mid.phi.eangvel 300
mid.phi.stall_th 4
mid.l.curr_mul 0.059999999
mid.l.curr_freq 900
mid.r.curr_mul 0.300000012
o.type 0
o.ekf.q_id 10000
o.ekf.q_iq 30000
o.ekf.q_eangvel 3000000
o.ekf.p0_idq 0.001
o.ekf.p0_eangvel 0.001
o.ekf.cc_comp 0
o.mras.gain 150000
bec.can_pwr_on TRUE
rcpwm.enable FALSE
rcpwm.pulse.bot 0.001
rcpwm.pulse.mid 0.0015
rcpwm.pulse.top 0.002
rcpwm.pulse.hyst 2.00E-05
vsi.pwm_freq 47000
exec_aux_command -1

Hi Gad,

Can you reproduce this issue on the ground manually sending fixed setpoint to the Myxa?
I suggest you to run motor identification on this Myxa one more time. Possibly, the motor parameters have changed a little bit.
Increase the ‘uavcan.esc_ttl’ parameter up to 0.7 sec as well. Myxa stops automatically the motor if it hasn’t received the setpoint from the autopilot for this period of time.

Would you recommend doing the motor identification process with the motor detached/attached to the gearbox/attached to the gearbox + prop?
Is it possible to run the identification process through the UAVCan, or only through kucher via USB? When the vehicle is fully assembled - getting to the USB port is not an easy task.

We’ll try to replicate the phenomenon and update…

It is recommended to carry out the motor identification procedure without any load (gearboxes, propellers detached).
You can run the motor identification procedure via UAVCAN protocol by setting parameter exec_aux_command to 1002.

Thanks @anon81208224
Re-tuned the Myxa with gearbox and props attached (it looked as if these parameters produce smoother operation than the parameters we got after tuning without anything attached on the motor)
Also - the some of the Myxas were having trouble starting up the motor so I tweaked the spinup parameters a bit.
After that we got smooth startup and operation and performed two flights without a single error count.
FYI:
The discussed Myxa’s parameters without any load:

uavcan.node_id integer 53
uavcan.esc_index integer 3
uavcan.esc_ttl real 0.5
uavcan.esc_sint real 0.050000001
uavcan.esc_sintp real 0.5
uavcan.esc_rcm integer 2
uavcan.esc_revrs boolean FALSE
rcpwm.ttl real 0.300000012
rcpwm.ctl_mode integer 2
rcpwm.reverse boolean FALSE
ctl.spinup_durat real 1.5
ctl.num_attempts integer 100
ctl.vm_cci_comp boolean FALSE
ctl.vm_oversatur boolean FALSE
ctl.pwron_slftst boolean FALSE
ctl.hard_stop boolean FALSE
ctl.vm_pppwm_thr real 0.949999988
ctl.field_weaken boolean FALSE
ctl.fw_v_boost real 1.200000048
m.num_poles integer 28
m.max_current real 28
m.max_id_current real 0
m.min_current real 0.100000001
m.spup_curr_begn real 2
m.spup_curr_end real 0.25
m.flux_linkage real 0.001773993
m.resistance real 0.058722541
m.induct_direct real 2.37E-05
m.induct_quadrat real 2.37E-05
m.min_eangvel real 400
m.max_eangvel real 17500
m.current_ramp real 100
m.voltage_ramp real 15
m.eangvel_accel real 6000
m.eangvel_decel real 5000
m.eangvel_ctl_kp real 0.003
m.eangvel_ctl_ki real 0.005
m.eangvel_ctl_kd real 1.00E-06
m.current_ctl_bw real 0.050000001
m.bemf_ctl_kp real 9.600000381
m.bemf_ctl_ki real 0.949999988
m.fw_evel_hyst real 100
mid.phi.curr_mul real 0.300000012
mid.phi.eangvel real 300
mid.phi.stall_th real 4
mid.l.curr_mul real 0.059999999
mid.l.curr_freq real 900
mid.r.curr_mul real 0.300000012
o.type integer 0
o.ekf.q_id real 10000
o.ekf.q_iq real 30000
o.ekf.q_eangvel real 3000000
o.ekf.p0_idq real 0.001
o.ekf.p0_eangvel real 0.001
o.ekf.cc_comp real 0
o.mras.gain real 150000
bec.can_pwr_on boolean TRUE
rcpwm.enable boolean FALSE
rcpwm.pulse.bot real 0.001
rcpwm.pulse.mid real 0.0015
rcpwm.pulse.top real 0.002
rcpwm.pulse.hyst real 2.00E-05
vsi.pwm_freq real 47000
exec_aux_command integer -1

And with GB and props attached:

uavcan.node_id integer 53
uavcan.esc_index integer 3
uavcan.esc_ttl real 0.5
uavcan.esc_sint real 0.050000001
uavcan.esc_sintp real 0.5
uavcan.esc_rcm integer 2
uavcan.esc_revrs boolean FALSE
rcpwm.ttl real 0.300000012
rcpwm.ctl_mode integer 2
rcpwm.reverse boolean FALSE
ctl.spinup_durat real 0.5
ctl.num_attempts integer 100
ctl.vm_cci_comp boolean FALSE
ctl.vm_oversatur boolean FALSE
ctl.pwron_slftst boolean FALSE
ctl.hard_stop boolean FALSE
ctl.vm_pppwm_thr real 0.949999988
ctl.field_weaken boolean FALSE
ctl.fw_v_boost real 1.200000048
m.num_poles integer 28
m.max_current real 28
m.max_id_current real 0
m.min_current real 0.100000001
m.spup_curr_begn real 5
m.spup_curr_end real 0.6
m.flux_linkage real 0.001761633
m.resistance real 0.05512942
m.induct_direct real 2.39E-05
m.induct_quadrat real 2.39E-05
m.min_eangvel real 400
m.max_eangvel real 17500
m.current_ramp real 100
m.voltage_ramp real 15
m.eangvel_accel real 6000
m.eangvel_decel real 5000
m.eangvel_ctl_kp real 0.003
m.eangvel_ctl_ki real 0.005
m.eangvel_ctl_kd real 1.00E-06
m.current_ctl_bw real 0.050000001
m.bemf_ctl_kp real 9.600000381
m.bemf_ctl_ki real 0.949999988
m.fw_evel_hyst real 100
mid.phi.curr_mul real 0.300000012
mid.phi.eangvel real 300
mid.phi.stall_th real 4
mid.l.curr_mul real 0.059999999
mid.l.curr_freq real 900
mid.r.curr_mul real 0.300000012
o.type integer 0
o.ekf.q_id real 10000
o.ekf.q_iq real 30000
o.ekf.q_eangvel real 3000000
o.ekf.p0_idq real 0.001
o.ekf.p0_eangvel real 0.001
o.ekf.cc_comp real 0
o.mras.gain real 150000
bec.can_pwr_on boolean TRUE
rcpwm.enable boolean FALSE
rcpwm.pulse.bot real 0.001
rcpwm.pulse.mid real 0.0015
rcpwm.pulse.top real 0.002
rcpwm.pulse.hyst real 2.00E-05
vsi.pwm_freq real 47000
exec_aux_command integer -1