Duet3D Logo Duet3D
    • Tags
    • Documentation
    • Order
    • Register
    • Login

    Debug tips

    Scheduled Pinned Locked Moved
    Firmware developers
    2
    16
    701
    Loading More Posts
    • Oldest to Newest
    • Newest to Oldest
    • Most Votes
    Reply
    • Reply as topic
    Log in to reply
    This topic has been deleted. Only users with topic management privileges can see it.
    • benjamin.forestundefined
      benjamin.forest
      last edited by

      Hi,

      As mentionned in a previous post, I'm struggling with something which seemed simple on a first glance but is a real pain in reality, ie adding an "inverse delta model" in kinematics.
      This is because the delta kinematics logic is actually being disseminated in the firmware (search for isDeltaMovement for example).

      I am not sure to perfectly understand why the DDA needs to know it is performing a delta movement, but I am encountering difficulties to understand what's going on, and where my motion fails.

      Do you have any tips about how to efficiently debug my kinematics, without adding debugPrintf, or M111 commands ?

      All the best,

      1 Reply Last reply Reply Quote 0
      • benjamin.forestundefined
        benjamin.forest
        last edited by benjamin.forest

        Note that I take any advice or documentation about DDA, DriveMovement and algorithm used as well 🙂

        1 Reply Last reply Reply Quote 0
        • dc42undefined
          dc42 administrators
          last edited by

          The DDA needs to know whether it is doing a delta movement so that it can set up the DM objects for the tower motors to do quadratic movements instead of linear movements.

          You can enable Move and DDA debug using the M111 command, to get the DDA and DM info sent to USB. This will slow down motion, but that shouldn't matter if you are only debugging basic kinematics.

          Duet WiFi hardware designer and firmware engineer
          Please do not ask me for Duet support via PM or email, use the forum
          http://www.escher3d.com, https://miscsolutions.wordpress.com

          1 Reply Last reply Reply Quote 0
          • benjamin.forestundefined
            benjamin.forest
            last edited by

            Thanks for your answer. I'm aware of M111 commands but they havent been that usefull so far, my problem doesn't seem to reach them.

            Any doc on DDA / DriveMovement general principles ? I get it that it is responsible for motion trajectory planning, but can't get a general view of their flow ...

            All the best

            1 Reply Last reply Reply Quote 0
            • dc42undefined
              dc42 administrators
              last edited by

              The only documentation is in the comments. Basically, the DDA summarises the movement, and the DMs contain the detail for each motor.

              When initially created, DDAs are in a flexible state so that they can adapted to merge into the move that follows. Shortly before the move is due to happen, Prepare is called, which switches the DDA into the frozen state and stores a number of pre-calculated parameters in the DM to speed up the step calculations.

              There are three versions of Prepare for DMs, for linear axis motors, delta tower motors, and extruder motors.

              Can you provide a sketch of your kinematics?

              HTH David

              Duet WiFi hardware designer and firmware engineer
              Please do not ask me for Duet support via PM or email, use the forum
              http://www.escher3d.com, https://miscsolutions.wordpress.com

              1 Reply Last reply Reply Quote 0
              • benjamin.forestundefined
                benjamin.forest
                last edited by

                Thanks,
                A small video shows our printer in motion : https://youtu.be/gORqC7tfNXI?t=22.

                Basically it is a LinearDelta, where the Head is fixed, and the bedplate moves. The only difference from a model point of view is a -Z instead of Z in CartesianTMotorSteps / MotorStepsToCartesian.

                benjamin.forestundefined 1 Reply Last reply Reply Quote 0
                • benjamin.forestundefined
                  benjamin.forest @benjamin.forest
                  last edited by

                  I've tried three strategies :

                  Invert Z in LinearDelta Model
                  Works, but X/Y moves in head coordinate system triggers wrong direction for motors. Leads to a strongly parabolic bedplate.

                  Change Linear model and inverse motors directions
                  Works for Z, but refuse motion for some axes in X/Y motion (dsK in DriveMovement taking negative values). Leads to only one axis on three moving for an Y motion for example.

                  Change Z at the source, in G1 command handling
                  Not interesting, but works. But create other problems (appart from not being maintainable), such as handling all function that need inverted Z.

                  1 Reply Last reply Reply Quote 0
                  • benjamin.forestundefined
                    benjamin.forest
                    last edited by

                    I suppose I mp.delta parameters are miscalculated maybe ?

                    1 Reply Last reply Reply Quote 0
                    • benjamin.forestundefined
                      benjamin.forest
                      last edited by

                      I note as well that for pure Z motion, kinematics does not seem to be taken into account ...

                      dc42undefined 1 Reply Last reply Reply Quote 0
                      • dc42undefined
                        dc42 administrators
                        last edited by dc42

                        At first glance it appears to me that you need to invert all of the X, Y and Z coordinates before transforming them through the kinematics matrix. Similarly, you need to reverse the signs after doing a forward transformation.

                        Alternatively, I think (but I am not sure) that taking the alternate solution of the forward and inverse kinematics equations may work. The equations are quadratic, so they have two solutions. The solution used by the standard delta kinematics assumes that the effector is at the lower of the two possible positions. If you imagine a delta where the nozzle is on the effector but the carriages are below the effector (and somehow the bed doesn't get in the way of the rods), I think this may be equivalent to your mechanics. Do you agree?

                        I can review the maths to see where the sign of a term would need to be changed.

                        Duet WiFi hardware designer and firmware engineer
                        Please do not ask me for Duet support via PM or email, use the forum
                        http://www.escher3d.com, https://miscsolutions.wordpress.com

                        1 Reply Last reply Reply Quote 0
                        • dc42undefined
                          dc42 administrators @benjamin.forest
                          last edited by

                          @benjamin-forest said in Debug tips:

                          I note as well that for pure Z motion, kinematics does not seem to be taken into account ...

                          Pure Z motion on a delta is treated the same as any other motion.

                          Duet WiFi hardware designer and firmware engineer
                          Please do not ask me for Duet support via PM or email, use the forum
                          http://www.escher3d.com, https://miscsolutions.wordpress.com

                          1 Reply Last reply Reply Quote 0
                          • benjamin.forestundefined
                            benjamin.forest
                            last edited by

                            Thanks for your time, I really appreciate it.

                            About the model, I agree that this is equivallent if the carriage are below the end effector. This is what I tried when I inversed motors directions. Maybe I screwed up with my model, though.

                            About pure Z motion :line 117 of DriveMovement.c, a comment about pure Z movement let me think that maybe it was handled differently ?

                            A few more questions if you have time, since i'm trying to read the code to try encircle my problem :

                            • It seems that LinearDelta does not use segmentation (GCodes.cpp, l.2047). I was thinking that segmentation was typically used for non-linear robots. What do I miss ? Is segmentation done somewhere else ? Probably in DDA, but where ?
                            • What does DDA stands for ? Wikipedia propose "Discontinuous deformation analysis", but that does not seem to correspond ;). Looking forward in results I found Digital differential analyzer, which seems better ! Is that correct ?
                            • So if I undestand correctly, DDA is performing two things : Motion planning, and rasterisation. Correct ?
                            • I'm a little lost with the functions Prepare, PrepareDeltaAxis, CalcNextStepDelta, CalcNextStepTimeDeltaFull. Are they following a known algorithm ?

                            My problem seems to come from DriveMovement.cpp, around line 527 : dsK < 0.
                            When I try a simple G1 Y10 motion for example, dsK is < 0 for two of my three axes, leading to bad motion. Do you know what it could mean ?

                            All the best,

                            dc42undefined 1 Reply Last reply Reply Quote 0
                            • benjamin.forestundefined
                              benjamin.forest
                              last edited by

                              any tips about dsK signification ?
                              All the best,

                              1 Reply Last reply Reply Quote 0
                              • dc42undefined
                                dc42 administrators @benjamin.forest
                                last edited by

                                @benjamin-forest said in Debug tips:

                                Thanks for your time, I really appreciate it.

                                About the model, I agree that this is equivallent if the carriage are below the end effector. This is what I tried when I inversed motors directions. Maybe I screwed up with my model, though.

                                I've taken a fresh look at this, and it appears to me that all you need to do is to invert (change sign of) the X, Y and Z inputs to the inverse transform, and invert the outputs from the forward transform. I think that should automatically sort out the segment-free delta motion calculations too.

                                About pure Z motion :line 117 of DriveMovement.c, a comment about pure Z movement let me think that maybe it was handled differently ?

                                It's special-cased there, but only because the general calculation would need to evaluate 0/0 for pure Z motion.

                                A few more questions if you have time, since i'm trying to read the code to try encircle my problem :

                                • It seems that LinearDelta does not use segmentation (GCodes.cpp, l.2047). I was thinking that segmentation was typically used for non-linear robots. What do I miss ? Is segmentation done somewhere else ? Probably in DDA, but where ?

                                Unlike most (perhaps all) other 3D printer firmwares, RepRapFirmware does not use segmentation to approximate linear delta kinematics. Instead it calculates the required quadratic motion.

                                • What does DDA stands for ? Wikipedia propose "Discontinuous deformation analysis", but that does not seem to correspond ;). Looking forward in results I found Digital differential analyzer, which seems better ! Is that correct ?

                                It originally stood for Digital differential analyzer, but that is a misnomer because RRF no longer uses the Bresenham approximation.

                                • So if I undestand correctly, DDA is performing two things : Motion planning, and rasterisation. Correct ?

                                Just motion planning and execution.

                                • I'm a little lost with the functions Prepare, PrepareDeltaAxis, CalcNextStepDelta, CalcNextStepTimeDeltaFull. Are they following a known algorithm ?

                                The algorithm comes from solving the equations of linear motion convoluted with the delta kinematics equations. Basic high school maths (quadratic equations).

                                My problem seems to come from DriveMovement.cpp, around line 527 : dsK < 0.
                                When I try a simple G1 Y10 motion for example, dsK is < 0 for two of my three axes, leading to bad motion. Do you know what it could mean ?

                                I did a quick analysis and I decided that what you needed to do was to invert the X, Y and Z coordinates before feeding them into the inverse kinematics equations, and again when they come out of the forward kinematics equations. However, if you invert just Z then I think it will still work, although of course the X and Y axes will be mirrored. So I suggest that is what you try. It means that positive raw motor movements will raise the carriages, which is what RRF expects, and you will need to home the carriages using negative (downwards) raw motor moves.

                                If your current setup is for positive motor movement to move the carriages down, then I think the sign of h0minusZ0 would be wrong when mp.delta.hmz0sk is calculated, which I think could lead to dsk being negative.

                                Duet WiFi hardware designer and firmware engineer
                                Please do not ask me for Duet support via PM or email, use the forum
                                http://www.escher3d.com, https://miscsolutions.wordpress.com

                                1 Reply Last reply Reply Quote 0
                                • benjamin.forestundefined
                                  benjamin.forest
                                  last edited by

                                  Great thank you !
                                  I'll try right away.

                                  It's really cool to calculate the quadratics equations, I didn't thought of it.

                                  1 Reply Last reply Reply Quote 0
                                  • benjamin.forestundefined
                                    benjamin.forest
                                    last edited by

                                    It doesn't work.

                                    I think it is linked to the calculation method : we are using directionVector, and it is calculated without using kinematics. So I guess everything after this (DDA.cpp, ~line 300) is miscalculated. Notably afterPrepare.cKc will have the wrong sign when hmz0scK is calculated in DriveMovement.c, ~l542, as you guessed earlier. My problem is that changing my model won't change that.

                                    Besides, I thougth about calucations performed in PrepareDeltaAxis and CalcNextStepTimeDeltaFull, but I do not manage to get the full picture. I can link tower position to motion direction and the percentage of accomplished motion, but that does not adds up with the code nicely. I get things in common, like A, B, aA, bB, but I'm still missing some pieces of the puzzle.

                                    I don't get where the speed/accelerations, that seemed to be calculated in cartesian tool coordinate system are translated into articular one either.

                                    Sorry if my questions seems naive.

                                    All the best,

                                    1 Reply Last reply Reply Quote 0
                                    • First post
                                      Last post
                                    Unless otherwise noted, all forum content is licensed under CC-BY-SA