Kinematics and Delta Robot

More
01 May 2019 05:30 - 02 May 2019 02:49 #132413 by Sockheaven
Hi Everyone,
This is my first foray into CNC anything, and can already tell I've bit off quite a challenge.
I work in servo drive development, specifically in controls, so I have that part down, but the rest (including Linux) is foreign to me.

I acquired a Delta Robot with high resolution servo motors and 25:1 gearboxes:


And i have servo drives i have configured for step/direction inputs:


And I plan to mount a laser to the delta and use it for a laser etching machine.

So far, using all the tutorials I could find so far, I've been able to:
  • Install Linux and locate a machine with ~15000us jitter
  • Using Debian 9.8 running x64 with PREEMPT_RT
  • Installed LinuxCNC 2.7.14
  • Configure Parrallel port for three axis step/dir
  • Servo drives are receiving step/dir signals and they move the correct distance LinuxCNC moves

Now, for the thing I have not been able to figure out:
How to setup the inverse kinematics??

I've been through IK work before with Scara robots and seen some sample Delta IK code, but I'm confused on how to utilize the kinematics layer in LinuxCNC.

Step by Step guides seem sparse and I seem to have run out of things to try.

Any assistance would be greatly appreciated!

Best Regards,
Paul
Attachments:
Last edit: 02 May 2019 02:49 by Sockheaven. Reason: photos missing

Please Log in or Create an account to join the conversation.

More
02 May 2019 05:49 #132486 by pl7i92
Replied by pl7i92 on topic Kinematics and Delta Robot
Hi
Welcome
First are you driving the servos with step/DIR signals
loss of Speed
you shoudt go for a MESA board 7i77 for real servo with encoders
or a 7i96 board for Steppers only
the kinetics is online there are also configs that show you in MASTER 2.8 alredy configured just hook up your pins as you need them
forum.linuxcnc.org/10-advanced-configura...lta-robot-kinematics
good point to start

Please Log in or Create an account to join the conversation.

More
02 May 2019 16:20 - 02 May 2019 16:20 #132545 by Sockheaven
Thanks for the welcome!

"First are you driving the servos with step/DIR signals"
Yes I am, I know this is not ideal, I am sacrificing a lot of the high performance drive loops as well as the 24bit feedbacks on the motors. But since this is my first attempt at anything cnc or linux, I thought this would be a good baby step.
I had pre-emptively bought a 7i92M board as i had planned to run this on a laptop without a parallel port - but i couldn't get the RT latency test to get under 300us (despite it being a pretty high performance laptop it had intermittent spikes i couldn't nail down).

I did stumble on some posts about someone having a branch of LinuxCNC supporting EtherCat - which would be the logical next step since I can configure these servo drives for nearly any industry fieldbus (ECat, CAN, Profinet, EthernetIP, and SynqNet).
But like I said, baby steps...

As for the Kinematics; "good place to start"
I stumbled upon the thread you mentioned already along with the nice deltakins.c code which looks perfect. However I couldn't figure out what to do with it.
I also stumbled upon this thread which seemed eerily similar to my troubles:
forum.linuxcnc.org/24-hal-components/327...matics-again?start=0

He also was encouraged to pull the master 2.8 version instead of the released stable version of 2.7.

Is this what you are alluding to with your reference of MASTER 2.8?

While being a seasoned Windows slave/developer and embedded developer for the better part of 2 decades, I've never even dipped a toe in Linux development so I don't even know where to start (it took me a few frustrating nights to figure out how to get linux switched to a RT kernel and run the latency test to pass well with boot modifications).

I have't been able to find a step-by-step guide to compiling the deltakins and installing it/using it.

Is this setup/structure significantly different/easier in the master build 2.8?
Last edit: 02 May 2019 16:20 by Sockheaven. Reason: spelling

Please Log in or Create an account to join the conversation.

More
02 May 2019 17:15 - 02 May 2019 17:15 #132548 by PCW
Replied by PCW on topic Kinematics and Delta Robot
300 usec is probably OK as long as you can reliably run a Ethernet
servo thread at 1 KHz or so, even 500 Hz may be OK if you do not have
very high joint acceleration.
Last edit: 02 May 2019 17:15 by PCW.

Please Log in or Create an account to join the conversation.

More
02 May 2019 21:28 #132567 by Sockheaven
Ok Thanks, I'll keep that in mind - tried 6 machines and just stuck with the machine that gave me the lowest jitter. I put windows back on that machine in the meantime, but I can always go back.

Right now my challenge is learning how to compile and install this deltakins module (the laptop would also need this).

I'm not sure what the frequency limitation of the parallel port is, but the high speed digital inputs on my servo drives is 3MHz, so I should be able to get something working.

I'm closing the Position loop on the drive at 4kHz and the Velocity loop at 16kHz and electronically gearing to a Step/Dir input. I have quite a bit of tuning/filtering available in those loops so I can handle a heavily quantized input coming in on the step/dir channel.

Please Log in or Create an account to join the conversation.

More
03 May 2019 01:05 #132586 by andypugh
Replied by andypugh on topic Kinematics and Delta Robot
If you install the 2.8 (development) version of LinuxCNC than "rotarydeltakins" is built-in.

You just need
[KINS]
...
KINEMATICS = rotarydeltakins
...
In the INI file. If you create a generic config then that will use trivkins. You just need to edit one entry to say rotarydeltakins.

It seems that the kinematics creates a set of HAL parameters which you need to "setp" to the correct numbers for your robot in the HAL file.

github.com/LinuxCNC/linuxcnc/blob/master...otarydeltakins.c#L68

Suggests that you should see pins called:
rotarydeltakins.platformradius
rotarydeltakins.thighlength
rotarydeltakins.shinlength
rotarydeltakins.footradius

I don't know if that is a standard naming scheme, but it seems pretty self-explanatory.

Please Log in or Create an account to join the conversation.

More
07 May 2019 05:42 #133025 by Sockheaven
Thanks for all the info.
Finally got some time to look at this some more and was able to do the following:
  • Switch to LinuxCNC 2.8
  • Modified INI:
    Changed KINEMATICS=rotarydektakins
    Changed all Joint TYPE=ANGULAR (was linear)
  • Modified HAL and added the following commands:
    setp rotarydeltakins.platformradius 63.5
    setp rotarydeltakins.thighlength 115.0
    setp rotarydeltakins.shinlength 358.0
    setp rotarydeltakins.footradius 60.6
no other changes made to files, let me know if i missed something.

After re-starting LinuxCNC, I noticed that the manual control changed from Axis to Joint:


Next Question:
I notice that when i try to test/jog the axes, I am only jogging the individual joint.

Is there a way to test in machine space instead?

I was hoping to be able to jog in X/Y/Z machine space and make sure the individual servo drives were receiving the correct inverse kinematics values before i connect up the real motors.

I figure once i verify the IK is working correctly, then i can start working out what my home positions need to be. I dont have any home switches or anything. I was thinking i'd just run a homing routine on the servo drives manually, then tell LinuxCNC that it's been homed, but i'm not quite sure how homing will work with the inverse kinematics.

Thanks again guys
-Paul
Attachments:

Please Log in or Create an account to join the conversation.

More
07 May 2019 10:23 #133046 by andypugh
Replied by andypugh on topic Kinematics and Delta Robot
It ought to switch automatically to cartesian mode after homing.
If not, then the $ keyboard shortcut should do it.
The following user(s) said Thank You: Sockheaven

Please Log in or Create an account to join the conversation.

More
09 May 2019 03:39 - 09 May 2019 03:40 #133225 by Sockheaven
Thanks Andy, it didn't occur to me i needed to Home, but I can see that logic now.

Ok, I homed the axes and ran into an issue where the axes would start outside the bounds I defined for software limits, presumably due to the IK math, but I'm not certain.

I modified the bounds so that Home (0,0,0) is in the center of the workspace instead of the lower corner of the workspace and that problem went away.

Next, I'm noticing my scaling is off, so ignore that in the attached files. I suspect i need to reconfigure the resolution counts to incorporate the gearboxes. It appears the IK math assumes a degree of motion at the "joint" and not the motor shaft. So I think my resolution/motion distance errors makes sense until I rework the scaling.

The only thing I can't seem to track down at the moment is that after homing, the Z Machine Axis starts at -338 mm instead of 0 like X and Y.
Further, it is the only axis I cannot Jog - both X and Y can be jogged, see below:


Did i mess something up in my config?
specifically with jogging, but I'm also puzzled on why it's setting the origin to that -338.029, i guess it could be a result of some IK calculation, but not sure.

HAL/INI attached

File Attachment:

File Name: my-mill.hal
File Size:4 KB

File Attachment:

File Name: my-mill.ini
File Size:2 KB
Attachments:
Last edit: 09 May 2019 03:40 by Sockheaven. Reason: clarification

Please Log in or Create an account to join the conversation.

More
09 May 2019 17:53 #133261 by andypugh
Replied by andypugh on topic Kinematics and Delta Robot
I haven't used rotarydeltakins, but -338 sounds pretty much right for the end-effector position when homed, as it is close to the "shin length" of your config.

I suspect that you need to set the Z axis limits to be -338 to -473 (shin + thigh). Don't worry about the absolute positions, your working coordinate system can be centred anywhere you want with G54(etc) offsets.
The following user(s) said Thank You: Sockheaven, slckzbn

Please Log in or Create an account to join the conversation.

Time to create page: 0.153 seconds
Powered by Kunena Forum