Update on delta motion in custom kinematics class
-
The standard delta kinematics class assumes that the first N axes are delta axes, where N defaults to 3 but can be increased by specifying multiple values for the L parameter in the M665 command. Any additional axes that you create are linear axes. There was a bug with this many firmware versions ago, but that was fixed in response to a report by one user, and AFAIK he/she is now using the additional axis successfully.
So I don't see why you are not able to use the standard delta kinematics. Can you explain?
I don't see how lines 1118-1132 in DDA.cpp would cause the problem. What those lines do is to set up additional parameters in the 'params' block and one additional parameter in the DDA. Those parameters are used only by DriveMovement objects that refer to the delta axes. They do not replace values used by linear axes.
Have you defined function GetMotionType correctly for your kinematics?
-
Thanks for the reply. I'm sure I am wrong about the problematic lines. I just tried following isDeltaMode until I stopped seeing things that made sense to me.
Unfortunately I don't think I can use the standards Delta kinematics because when I make a movement using one of the extra axes often the Delta axes must move too. For instance, a movement of G1 V20 moves the print bed 20mm in the +Y direction. My kinematics class allows the Delta printer to track that movement without needing a G1 Y20 movement as well. This way I can use regular G Code to print on a moving surface.
I will double check today if I implemented the motion type correctly for my axes today, but I think I have.
Everything works great, but the Delta moves in arcs. I've been trying to make sure I only do small movements, but lately I've had trouble getting prints started if they have straight edges because the G Code points are far apart and in between points the nozzle jams into the print surface.
I will try adding additional axes using the M command. I saw that in the last update but since my class was working (minus this problem) I didn't try that.
-
@gizmotronx5000 said in Update on delta motion in custom kinematics class:
Unfortunately I don't think I can use the standards Delta kinematics because when I make a movement using one of the extra axes often the Delta axes must move too. For instance, a movement of G1 V20 moves the print bed 20mm in the +Y direction. My kinematics class allows the Delta printer to track that movement without needing a G1 Y20 movement as well. This way I can use regular G Code to print on a moving surface.
I think you mean that when you include V20 in a move, you want to implicitly add Y-20 so that the belt motion won't affect the print. That does indeed mean that you need new kinematics, unless you preprocess the GCode to add or adjust the Y coordinates when V movement is present.
I will try adding additional axes using the M command. I saw that in the last update but since my class was working (minus this problem) I didn't try that.
That's for adding additional delta axes, not linear axes.
What I intend is that the firmware calls GetMotionType for each axis to decide whether to treat that axis as a linear or a delta axis. The DriveMovement objects will be set up differently depending on whether the axis is linear or delta, but the DDA should contain enough information for both types of axis. It works OK for extruders, which are basically linear axes plus optional pressure advance. The IsDeltaMode function is called just once, in DDA.cpp to set up flags.isDeltaMovement. That flag is only interrogated in three places. Note, this is in firmware 2.03RC1, and it sounds to me that you may be using much older firmware.
-
I'm actually using 2.03beta2 so not crazy old, but behind the current version. I'll update today.
I think you mean that when you include V20 in a move, you want to implicitly add Y-20 so that the belt motion won't affect the print. That does indeed mean that you need new kinematics, unless you preprocess the GCode to add or adjust the Y coordinates when V movement is present.
That's a good way of putting it. That's pretty much exactly what I've done. By performing a series of coordinate transformations within the kinematics class I have made my G code processing much easier. Basically I can print standard G code and the transformations keep track of the proper coordinate system.
My GetMotionType function is
MotionType LinearDelta7DKinematics::GetMotionType(size_t axis) const
{
return (axis < numTowers) ? MotionType::segmentFreeDelta : MotionType::linear;
}I am only using 3 delta axes and configuring them with M665 R110.6 L340.5 B90 H120.35, which should set numTowers to 3.
-
Double checking basics:
Are you "adjusting" the Cartesian Y to compensate for V movement? That is, NOT adjusting the "Y Tower" delta move?
-
@danal Agreed, it's always good to check the basics. I am sure that I'm adjusting the machine position, not the motor position. I'm not confident that my kinematics class is 100% configured right, but all of the motion I need works. The "implied" moves of the delta all happen properly, except that the special case delta straight line motion doesn't work; the print head travels in an arc.
Here is a list of my modifications so far to the firmware, which work.
I had to modify the GCodes2.cpp file for M665 first. It kept forcing my printer into KinematicsType::linearDelta when it saw an M665 command, so I added another case for my kinematics class number. This work fine and M122 reports back that I am in the right mode, plus my transformations happen correctly, so I know the right mode is being used.
I copied LinearDeltaKinematics.h/cpp and created my own versions, modifying Recalc(), the various forward/inverse transform functions, CartesianToMotorSteps() and MotorStepsToCartesian(), removed basically any function relating to auto calibration (for now until I figure out a way to add them back if I get to it).
I've created homing files for everything, and configured the extra axes in config.g
I also use:
MotionType LinearDelta7DKinematics::GetMotionType(size_t axis) const
{
return (axis < numTowers) ? MotionType::segmentFreeDelta : MotionType::linear;
}At this point the motion all works for small movements. If I could force my slicer to only make <2mm moves I would be set. Up to this point it makes sense that the print head travels in an arc because I haven't told Move to treat it as a delta.
In an attempt to fix the segmentFreeDelta motion I made these additional changes that have not worked:
In Move.h:
bool IsDeltaMode() const { return (kinematics->GetKinematicsType() == KinematicsType::linearDelta) || (kinematics->GetKinematicsType() == KinematicsType::myKinematics); }This causes all of the motion involving the 3 delta axes to be jumpy and inaccurate for all moves that aren't purely Z. The extra linear axes all work fine still, but the delta no longer tracks the V axis motion like before. I'm sure something in my kinematics class could be causing this, but it seems odd that the motion works fine when I treat all axes as linear and breaks when I try to incorporate the delta motion type.
I know this is very weird case. Thanks for all the help, I really appreciate it.
-
I think you may have been right anout those lines in DDA.cpp that you highlighted, specifically this one:
params.dparams = static_cast<const LinearDeltaKinematics*>(&(reprap.GetMove().GetKinematics()));
The static_cast is wrong in your case, because the kinematics is your own class, not the LinearDeltaKinematics class.
One possible solution may be to derive your own kinematics class from LinearDeltaKinematics.
-
I updated to version 2.03RC1, and the same thing happens. The only thing I really changed was added an override function of GetLinearAxes(), which doesn't seem to do anything yet. I copied the one from LinearDeltaKinematics. Looks like that is in the pipeline though, so I'll pay attention to that going forward.
Is my constructor correct to be:
MyKinematics::MyKinematics() : Kinematics(KinematicsType::myKinematics, -1.0, 0.0, true), numTowers(UsualNumTowers)
{
Init();
}or should I being doing something similar to rotary delta with segmented motion? Is that a valid work around? I could change all axes to be linear axes, but use segmented motion instead in the constructor. Would I need to change anything else if I tried that?
-
@dc42 said in Update on delta motion in custom kinematics class:
I think you may have been right anout those lines in DDA.cpp that you highlighted, specifically this one:
params.dparams = static_cast<const LinearDeltaKinematics*>(&(reprap.GetMove().GetKinematics()));
The static_cast is wrong in your case, because the kinematics is your own class, not the LinearDeltaKinematics class.
One possible solution may be to derive your own kinematics class from LinearDeltaKinematics.
Ooh boy. I'm really getting into it now aren't I? Derived classes sound familiar, but I should've taken more than 1 class of C++ in school. I'll look into that. Do you have any pointers on how to start? Are there any derived kinematics classes already in this project I can work from to understand? Thanks again.
-
or should I being doing something similar to rotary delta with segmented motion? Is that a valid work around? I could change all axes to be linear axes, but use segmented motion instead in the constructor. Would I need to change anything else if I tried that?
I just tried this to see what might happen. I changed my kinematics class to:
MyKinematics::MyKinematics() : Kinematics(KinematicsType::myKinematics, DefaultSegmentsPerSecond, DefaultMinSegmentSize, false), numTowers(UsualNumTowers)
{
Init();
}I took the definitions of the defaults from rotary delta kinematics, 100, and 0.2 respectively
I also changed GetMotionType to:
MotionType LinearDelta7DKinematics::GetMotionType(size_t axis) const
{
return MotionType::linear;
}Things mostly work now, but the motion is not entirely smooth. It is definitely trying to approximate a straight line, but not quite right. As far as I can tell all of the moves do at least arrive in the correct spot.