Additional axis to a hangprinter
-
Hello everybody!
Me and my team are working on a hangprinter with an extra twist. Instead of one d axis we basically have two, and the other d axis has slightly different kinematics. I've tried to stab the code by just adding one more axis in hangprinterkinematics.cpp and hangprinterkinematics.h which has lead to a small machine uprising incident (aka weird results) but everything is under control now (I changed the code back to what it was).
My question is how would one add the other d axis in the reprapfirmware code?
Thank you for you help!
-
Hi can you describe the kinematics you are trying to implement and how it did not work.
-
// some variables constexpr float DefaultAnchorA[3] = { 0.0, -1437.13, 392.0}; constexpr float DefaultAnchorB[3] = { 1244.59, 718.56, 392.0}; constexpr float DefaultAnchorC[3] = {-1244.59, 718.56, 392.0}; constexpr float zOffset = 392.0; //constexpr float DefaultAnchorDz = 3574.5906 - zOffset; constexpr float DefaultAnchorDz = 3312.4019; constexpr float DefaultAnchorFz = 3574.5906; constexpr float DefaultPrintRadius = 1500.0; // and the function I've tinkered with bool HangprinterKinematics::CartesianToMotorSteps(const float machinePos[], const float stepsPerMm[], size_t numVisibleAxes, size_t numTotalAxes, int32_t motorPos[], bool isCoordinated) const { float squaredLineLengths[HANGPRINTER_AXES]; squaredLineLengths[A_AXIS] = LineLengthSquared(machinePos, anchorA); squaredLineLengths[B_AXIS] = LineLengthSquared(machinePos, anchorB); squaredLineLengths[C_AXIS] = LineLengthSquared(machinePos, anchorC); squaredLineLengths[D_AXIS] = ( fsquare(machinePos[X_AXIS]) + fsquare(machinePos[Y_AXIS]) + fsquare(anchorDz - machinePos[Z_AXIS]) ); squaredLineLengths[F_AXIS] = ( fsquare(machinePos[X_AXIS]) + fsquare(machinePos[Y_AXIS]) + fsquare(anchorFz - machinePos[Z_AXIS]) ); char* axixes[5] = {"A axis", "B axis", "C axis", "D axis", "F axis"}; float linePos[HANGPRINTER_AXES]; for (size_t i = 0; i < HANGPRINTER_AXES; ++i) { linePos[i] = sqrtf(squaredLineLengths[i]) - lineLengthsOrigin[i]; if(i < 3){ debugPrintf("Lineposition %s : %f\n", axixes[i], linePos[i] + 1441,03); } else { debugPrintf("Lineposition %s : %f\n", axixes[i], linePos[i]); } } if (squaredLineLengths[A_AXIS] > 0.0 && squaredLineLengths[B_AXIS] > 0.0 && squaredLineLengths[C_AXIS] > 0.0 && squaredLineLengths[D_AXIS] > 0.0 && squaredLineLengths[F_AXIS] > 0.0) { motorPos[A_AXIS] = lrintf((float)linePos[A_AXIS] * (float)stepsPerMm[A_AXIS]); motorPos[B_AXIS] = lrintf((float)linePos[B_AXIS] * (float)stepsPerMm[B_AXIS]); motorPos[C_AXIS] = lrintf((float)linePos[C_AXIS] * (float)stepsPerMm[C_AXIS]); motorPos[D_AXIS] = lrintf((float)linePos[D_AXIS] * (float)stepsPerMm[D_AXIS]); motorPos[F_AXIS] = lrintf((float)linePos[F_AXIS] * (float)stepsPerMm[F_AXIS]); return true; } for (size_t i = 0; i < HANGPRINTER_AXES; ++i){ debugPrintf("Motor positions: %s, %f\n", axixes[i] , motorPos[i]); } // if (squaredLineLengths[A_AXIS] > 0.0 && squaredLineLengths[B_AXIS] > 0.0 && squaredLineLengths[C_AXIS] > 0.0 && squaredLineLengths[D_AXIS] > 0.0) // { // motorPos[A_AXIS] = lrintf(k0[A_AXIS] * (sqrtf(spoolRadiiSq[A_AXIS] + linePos[A_AXIS] * k2[A_AXIS]) - spoolRadii[A_AXIS])); // motorPos[B_AXIS] = lrintf(k0[B_AXIS] * (sqrtf(spoolRadiiSq[B_AXIS] + linePos[B_AXIS] * k2[B_AXIS]) - spoolRadii[B_AXIS])); // motorPos[C_AXIS] = lrintf(k0[C_AXIS] * (sqrtf(spoolRadiiSq[C_AXIS] + linePos[C_AXIS] * k2[C_AXIS]) - spoolRadii[C_AXIS])); // motorPos[D_AXIS] = lrintf(k0[D_AXIS] * (sqrtf(spoolRadiiSq[D_AXIS] + linePos[D_AXIS] * k2[D_AXIS]) - spoolRadii[D_AXIS])); // return true; // } return false; }
This is pretty much that I've done. We call the additional d axis "F axis". I also changed the array lengths in the hangprinterkinematics.h and added the AnchorFz there as well. Basically the F axis should just have different lengths, and the spool size is different.
I tried to get it working with same kinematics as the regular d axis so that the kinematics is the same but drive would be different (Not sure if I use the word drive correctly I'm little new with the vocabulary. But you know the channel where each motor is controlled). With this we got some unexpected results, we're still looking into it, it might be some other issue.
-
Hello PieTorque,
It was a while since I did any RRF coding, but I can post my immediate thoughts on the code you've posted.
It looks like you've made the F-axis a replica of the D-axis. That will not work.
On standard Hangprinters v1, v2, and v3, the D-axis is a special axis, which is treated differently in firmware than the ABC-axes.
The D-axis determines the direction of the Z-axis, so the D-anchor is by definition located in X=0, Y=0, Z=something.
By replicating the D-axis, you're forcing the F-axis to be located vertically (or rather Z-ly) above or below the D-axis, which will lead to line collision between D/F-line and D/F-anchor.I also see a typo "axixes" on line 33.
You need to make the F-axis a replica of one of the ABC-axes.
You also need to decide if you want to keep the special handling of the D-axis, or if you want to treat the D-axis like the ABCF-axes.The definition (or implicit assumption) of Dx=0 and Dy=0 in the code is helpful because it establishes a world coordinate system for all Hangprinter users. Or actually, another assumption is also needed to fully constrain the world coordinate system. I've used the convention that the A-anchor always lies on the negative y-axis, so A-anchor is located at X=0, Y=something negative, Z=something.
Both anchor location calibration and every G1 movement requires Hangprinter to have defined/constrained a world coordinate system.
It's a bit confusing that (Dx=0, Dy=0) is hard coded into hangprinterkinematics.cpp/h, while the other constraint (Ax=0, Ay=negative) is enforced by convention. I would recommend removing the special handling of the D-anchor and D-axis, so that all axes are equal. And then enforce constraints only by convention. If I had thought about that in 2018 you probably wouldn't have issues adding the F-axis now...
Keeping the same convention across the Hangprinter community is important, as it lets us use the same auto calibration routines, the same slicer profiles, and it lets us help each other out in general without always having to ask about each user's chosen world coordinate system conventions first.
Lastly a scroll through the code...
- Line 8 and 9: Make them similar to lines 3-5.
- Lines 20-31: Make them similar to lines 17-19.
- Line 33: axixes typo, and don't use literal 5. Use HANGPRINTER_AXES (which should be 5).
- Line 39: The last argument (03) is not printed. I guess the comma should have been a dot. I don't understand what you're doing there. The value 1441.03 is still different from the 1437.13 value in DefaultAnchorA and 1437.1 in DefaultAnchorB and DefaultAnchorC. It might be helpful for you to copy the logic you want to debug into a separate, smaller program that you can compile and test quickly in isolation. Then, instead of printf-debugging and risking bugs in the printf statements themselves in the big messy file, you can write C++ coded tests that look at the values you want to check after every code change.
- Line 47-54: The indentation is off.
- Line 55-57: Debug print squeezed in between two return statements will confuse future users.
- Line 58-68: Remove.
Best regards,
tobben -
Hello Tobben!
Thank you for checking the code. I know it's a mess right now with the typos and all. For now all the debugprintfs are just something we had needed for our testing. I'm most likely going to remove all of them and think it through intensely what kind of printf's I will be adding that would be actually helpful to everyone.
You're right that the kinematics can't be the same as the D axis, I will be copying one of the A B or C. But if the HANGPRINTER_AXES is 5, and I've added all the proper kinematics in the hangprinterkinematics.cpp is that all I need to do in order for the F_axis to work? Or is there something else that needs adjusting somewhere else? For example other files like kinematics.cpp or you name it?
Best regards
PieTorque -
The whole Hangprinter kinematics "should" be encapsulated in hangprinterkinematics.h/cpp, so if any other files need to be changed, then I'd call that an abstraction leak or a bug.
So the F-axis should work in the sense that it can respond properly to movement commands. However, to get torque mode and motor position readings (required if you want auto calibration of anchor locations), you need UART/convenience wires coupled into the ODrive that's driving the F-axis. (That is, if you're using ODrives.) Getting convenience wires working with a third ODrive would potentially require a lot of work.
You also need to map the step/dir pins properly in your config.g, and also configure the F-axis motor the same way as ABCD-motors are configured, but it sounded like you'd already looked into that since you've already made a test run on hardware. Just wanted to have it mentioned in this thread.
I also see, on lines 48-52, that you have hard coded away the line buildup compensation. You could achieve the same thing by simply configuring the buildup factor (I think it's called Q somewhere in config.g) to zero. You shouldn't need to purge the whole compensation feature from the source code. Anyways, I guess purging it gives you more control or peace of mind, and that you know what you're doing...
(The float casts on lines 48-52 are not needed since linePos and stepsPerMm already contains floats. Sorry, I have to.)
Good luck with your project!
Are you posting your progress somewhere, so I can follow you and learn more about your project?