Extruder motors unresponsive
-
Hi again
We had already some success in our everlasting battle with our cable-driven 3D-printer. The temp sensors work now and we managed to PID tuning the heaters after a few tweaks. That's ok.
Also our automated pellet dispenser works. The only thing still preventing us from extruding is the unresponsive extruder stepper.
I checked that the wiring should be ok.
Phase A & B are correctly wired on both extruder steppers. In case you wonder, we have the main Nema23 and a auxiliary Nema17 for pushing the pellets down the throat.Nonetheless we are seeing an error that phase A & B might be disconnected on drivers 0 & 1
Could it be the stepper cable length (15m)?
; Configuration file for testing Duet Ethernet and Wifi ; Communication and general M111 P1 S0 ; Debug off M550 XXX ; Machine name and Netbios name (can be anything you like) M551 XXX ; Machine password (used for FTP) ;*** If you have more than one Duet on your network, they must all have different MAC addresses, so change the last digits M540 XXX ; MAC Address ;*** Networking - Enable for both WiFi and Ethernet boards. M552 S1 ; Turn network on ;*** Ethernet networking: Adjust the IP address and gateway in the following 2 lines to suit your network M552 XXX ; (0 = DHCP) M554 XXX ; Gateway M553 XXX ; Netmask M555 P2 ; Set output to look like Marlin G21 ; Work in millimetres G90 ; Send absolute coordinates... M83 ; ...but relative extruder moves ;;;; HANGPRINTER SPECIALS (M669, M666) BEGIN HERE ;;;; M669 K6 ; This is a Hangprinter enables ABCDV-parameters in gcodes that refer to motors M584 V9 A6 B5 C7 D8 P5 ; map ABCDV-axes to ext driver pins (four visible) M584 E0:1:2:3:4 ; Regard all TMC2660s as extruder motor drivers M569 P0 S1 ; Drive 0 goes forwards M569 P1 S1 ; Drive 1 goes forwards M569 P2 S1 ; Drive 2 goes forwards M569 P3 S1 ; Drive 3 goes forwards M569 P4 S1 ; Drive 4 goes forwards M569 P5 S0 R1 T5:5:10:1 ; Drive 5 (A) goes forwards M569 P6 S0 R1 T5:5:10:1 ; Drive 6 (B) goes backwards M569 P7 S0 R1 T5:5:10:1 ; Drive 7 (C) goes forwards M569 P8 S0 R1 T5:5:10:1 ; Drive 8 (D) goes backwards M569 P9 S0 R1 T5:5:10:1 ; Drive 9 (V) goes backwards M669 A0:-1437.13:-216.00 ; Anchor Ax:Ay:Az M669 B1244.59:718.56:-216.00 ; Anchor Bx:By:Bz M669 C-1244.59:718.56:-216.00 ; Anchor Cx:Cy:Cz M669 D3706.1 ; Anchor D = Distance between the anchor pivot point D and the end effector pivot point D M669 P500 ; Printable radius M669 S200 ; Segments/sec M666 Q1 ; Line Spool up compensation = 1 M666 R50.1:65.1:65.1:65.1:65.1 ; Spool radii of A:B:C:D:V spools ; The following is assumed ; by the auto calibration script ; to be constant for all HP4s M666 U1:2:2:2:1 ; Mechanical advantages on ABCDV M666 O1:1:1:1:1 ; Number of lines per spool M666 L5:20:20:20:20 ; Motor gear teeth of ABCDV axes M666 H300:255:255:255:255 ; Spool gear teeth of ABCDV axes ; Adjust the following to match your ODrive settings M666 J32:32:32:32:32 ; Full steps per ABCDV motor revolution M350 X16 Y16 Z16 V16 E16:16 I1 ; Configure microstepping with interpolation M208 Z3706.1 ; set maximum Z at D anchor. See M669 ... D<number> M201 X6000 Y6000 Z6000 V6000 E250:250 ; Accelerations (mm/s^2) M203 X120000 Y120000 Z60000 V60000 E1200:1200 ; Maximum speeds (mm/min) M574 X2 Y2 Z2 V2 S1 ; set endstop configuration (all endstops at high end, active high) M906 X1200 Y1200 Z1200 V1200 E1900:1400 I30 ; Set motor currents (mA) and increase idle current to 60% M84 S30 ; Set idle timeout M566 X10000 Y10000 Z10000 V10000 E120:120 ; Maximum instant speed changes mm/minute ; Thermistors M305 P4 L25 H-70 X503 R2200 S"Metering" ; Put your own H and/or L values here to set the metering zone thermistor ADC correction M305 P3 L25 H-70 X504 R2200 S"Compression" ; Put your own H and/or L values here to set the compression thermistor ADC correction M305 P5 L25 H-70 X505 R2200 S"Feed" ; Put your own H and/or L values here to set the feed zone thermistor ADC correction M305 P6 L25 H-70 X506 R2200 S"Hopper" M307 H3 A123.4 C186.4 D16.1 S1.00 V0 ; Heater 3 settings M307 H4 A123.4 C186.4 D16.1 S1.00 V0 ; Heater 4 settings M307 H5 A123.4 C186.4 D16.1 S1.00 V0 ; Heater 5 settings M570 S300 ; Hot end may be a little slow to heat up so allow it 300 seconds ; Tool definitions M563 P0 S"Pellet Extruder" D0:1 H3:4:5:6 ; Define tool 0 M567 P0 E1:0.9 ; Set tool 0 mixing ratio for main motor and auxiliary motor G10 P0 S0 R0 ; Set tool 0 operating and standby temperatures M92 E420:420 ; Set extruder steps per mm M208 S1 Z-10.0 ; set minimum Z T0 ; select first hot end ; Enable Fan 1 thermostatic mode for heater 1 (E0 HEAT) at 45 degrees M106 P0 X150 T45 H6
-
what firmware version are you running?
what are the specs of the nema23 motors?
-
@Veti The firmware is 2.02 RC4 based on Torbjörn Ludvigsen's Hangprinter firmware, but with additional customization by us. None of them affect the E drives though.
The Nema23 spec are here https://www.omc-stepperonline.com/economy-planetary-gearbox/nema-23-stepper-motor-bipolar-l76mm-w-gear-raio-41-planetary-gearbox-23hs30-2804s-pg4.html?mfp=161-motor-nema-size[Nema 23]
-
whats your measured phase resistance with the 15m cable?
the steppers are speced at Phase Resistance: 1.13ohms
-
@Bloft-Design-Lab worth trying them with short cables directly to the Duet if you can do that without too much hassle.
Also you could try moving 1 of the motors to another driver (2,3,4 are unused i think), if that works try the other one.
This is not the cause of the problem but M584s should be before M669
https://duet3d.dozuki.com/Wiki/Gcode#Section_M584_Set_drive_mappingAlso please send M122 and put the results here, when the error is triggered.
-
-
@Veti said in Extruder motors unresponsive:
whats your measured phase resistance with the 15m cable?
the steppers are speced at Phase Resistance: 1.13ohms
The Nema23 has a phase resistance of 1.9 ohm (with the cable)
And the Nema17 3.8 ohm -
@T3P3Tony said in Extruder motors unresponsive:
Also please send M122 and put the results here, when the error is triggered.
Here you go.
Btw, one strange behavior that I noticed was the M669 K6 command. If I put the drive settings before it, the drives won't work as expected. I assume this is due to the Hangprinter custom code.
M122 === Diagnostics === RepRapFirmware for Duet 2 WiFi/Ethernet version 2.02RC4(RTOS) running on Duet WiFi 1.02 or later Board ID: 08DGM-9T6BU-FG3S0-7JKF2-3S86Q-TA5RF Used output buffers: 3 of 20 (8 max) === RTOS === Static ram: 28564 Dynamic ram: 98980 of which 0 recycled Exception stack ram used: 296 Never used ram: 3232 Tasks: NETWORK(ready,160) HEAT(blocked,1232) MAIN(running,3324) IDLE(ready,200) Owned mutexes: === Platform === Last reset 00:08:28 ago, cause: software Last software reset at 2021-02-25 12:01, reason: User, spinning module GCodes, available RAM 3104 bytes (slot 2) Software reset code 0x0003 HFSR 0x00000000 CFSR 0x00000000 ICSR 0x0441f000 BFAR 0xe000ed38 SP 0xffffffff Task 0x4e49414d Error status: 0 Free file entries: 10 SD card 0 detected, interface speed: 20.0MBytes/sec SD card longest block write time: 0.0ms, max retries 0 MCU temperature: min 28.4, current 28.8, max 29.1 Supply voltage: min 23.4, current 24.2, max 24.5, under voltage events: 0, over voltage events: 0, power good: yes Driver 0: standstill, SG min/max not available Driver 1: standstill, SG min/max not available Driver 2: standstill, SG min/max not available Driver 3: standstill, SG min/max not available Driver 4: standstill, SG min/max not available Date/time: 2021-02-25 12:09:55 Cache data hit count 1821651575 Slowest loop: 4.63ms; fastest: 0.07ms I2C nak errors 0, send timeouts 0, receive timeouts 0, finishTimeouts 0 === Move === Hiccups: 0, StepErrors: 0, LaErrors: 0, FreeDm: 240, MinFreeDm: 239, MaxWait: 501704ms, Underruns: 0, 0 Scheduled moves: 1, completed moves: 1 Bed compensation in use: none Bed probe heights: 0.000 0.000 0.000 0.000 0.000 === Heat === Bed heaters = 0 -1 -1 -1, chamberHeaters = -1 -1 Heater 3 is on, I-accum = 0.0 Heater 4 is on, I-accum = 0.0 Heater 5 is on, I-accum = 0.0 === GCodes === Segments left: 0 Stack records: 1 allocated, 0 in use Movement lock held by null http is idle in state(s) 0 telnet is idle in state(s) 0 file is idle in state(s) 0 serial is idle in state(s) 0 daemon is idle in state(s) 0 queue is idle in state(s) 0 autopause is idle in state(s) 0 Code queue is empty. === Network === Slowest loop: 22.75ms; fastest: 0.00ms Responder states: HTTP(0) HTTP(0) HTTP(0) HTTP(0) FTP(0) Telnet(0) Telnet(0) HTTP sessions: 1 of 8 - WiFi - Network state is running WiFi module is connected to access point Failed messages: pending 0, notready 0, noresp 0 WiFi firmware version 1.22 WiFi MAC address 84:f3:eb:82:db:ae WiFi Vcc 3.35, reset reason Turned on by main processor WiFi flash size 4194304, free heap 28808 WiFi IP address 192.168.43.109 WiFi signal strength -58dBm, reconnections 0, sleep mode modem Socket states: 0 0 0 0 0 0 0 0
-
that is not showing any errors with the stepper drivers....
-
Ok, I found the issue.
The steppers didn't work, because I had mapped all of the Duet drivers as extruders. Line 26 in our config. This is adopted from the Hangprinter config file.
I assumed that the drive number reflects the E-number in the Duet 2 wiring diagrams, but seems that this not the case. So, deleting the E0:1:2 from line 26 made the magic happen
Extruder is now ready. Finally!
But, then another issue surfaced. Again. It has nothing to do with Duet. One wire on our proto board had a bad solder joint and it got in contact with another pin (probably a power pin). The result was a fried Arduino Nano...
Trying to get replacement today. Can't wait