Re: [Emc-users] Problem with genserkins
2017-03-02 21:47 GMT+02:00 Charles Steinkuehler: > Thanks for the hints, it would have taken me quite a while to figure > all that out. Now I'll start plugging in numbers and toggling between > world and joint coordinates to see what's happening. > Well, I think I missed the fact that genser_kin_jac_fwd is also build using similar method: go_link_joint_set and then compute_jfwd That means if the correct forward kins is built the inverse still won't work until the jacobian is tweaked too. There's a workaround though: I used plain derivatives to calculate jacobian for pentapod kinematics where I could not find the correct symbolic form. ...maybe I'll even get brave and try to build the command-line version > of genserkins to assist with debugging! :) > That would be nice! I suspect they might have debugged genserkins too https://github.com/LinuxCNC/linuxcnc/blob/af15a4d90e1d51d5309db65fe1c9511e486df411/src/emc/kinematics/genserkins.c#L678 Genhexkins also had similar old code (until I cleaned it). Best regards, Andrew -- Check out the vibrant tech community on one of the world's most engaging tech sites, SlashDot.org! http://sdm.link/slashdot ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Problem with genserkins
On 3/2/2017 1:26 PM, Andrew wrote: > What this means for genserkins: everything is defined in genser_kin_fwd. > Tweaking it will tweak both forward and inverse kins. > > OK, first it uses go_link_joint_set for each joint and then > go_link_pose_build to get the robot pose... which uses go_pose_pose_mult to > build the pose from the first to the last joint. > So from the first look it seems that this method should output world AB > coordinates. Or it might output angles between the last pair of links? > Well now one just needs to figure it out... I'm not particularly good with > quaternions, which is exactly what is used in go_quat_quat_mult to > calculate pose.rot. Thanks for the hints, it would have taken me quite a while to figure all that out. Now I'll start plugging in numbers and toggling between world and joint coordinates to see what's happening. ...maybe I'll even get brave and try to build the command-line version of genserkins to assist with debugging! :) -- Charles Steinkuehler char...@steinkuehler.net signature.asc Description: OpenPGP digital signature -- Check out the vibrant tech community on one of the world's most engaging tech sites, SlashDot.org! http://sdm.link/slashdot___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Problem with genserkins
2017-03-02 18:01 GMT+02:00 Charles Steinkuehler: > Hmm...I see your point, but commanding an AB orientation in world > space via gcode would then require knowing the position of the first > joint (the base rotation of the whole arm), which is generated from > the commanded position via kinematics. In the simple Puma-like serial > arm I'm working with this might be possible, but in other > arrangements (where more than one axis is rotating around world Z) > there are multiple valid solutions, so you can't really infer exact > joint positions from the gcode. > > This really feels like something that either needs to be handled in > the machine kinematics, or the gcode needs to be directly controlling > the joints (pushing the kinematics off to the CAM system) unless I'm > missing something. > RIght, this task is not for a CAM. Unless it's a specific CAM for robots (not even sure, I have no experience with any or them). > > Any pointers for how to do this? I haven't gotten very far through > the "gomath" library yet, which is where most of the fun stuff seems > to be happening... > I looked to genserkins, and generally I see how it works. It computes genser_kin_fwd from DH parameters and joint values (using gomath lib) and passes it to kinematics_forward. Kinematics_inverse is more complicated. It builds a forward jacobian in compute_jfwd and then compute_jinv inverts it (oh, I just learned that gomath has go_matrix_inv but genhexkins has its own function for that, should try using gomath there). Then inverse kins is iterated. This is a common approach, pretty simple and reliable... unless the iterations fail, or matrix inverse fails :) (pumakins uses different approach, it calculates forward and inverse kins from equations for that particular robot type). What this means for genserkins: everything is defined in genser_kin_fwd. Tweaking it will tweak both forward and inverse kins. OK, first it uses go_link_joint_set for each joint and then go_link_pose_build to get the robot pose... which uses go_pose_pose_mult to build the pose from the first to the last joint. So from the first look it seems that this method should output world AB coordinates. Or it might output angles between the last pair of links? Well now one just needs to figure it out... I'm not particularly good with quaternions, which is exactly what is used in go_quat_quat_mult to calculate pose.rot. Best regards, Andrew -- Check out the vibrant tech community on one of the world's most engaging tech sites, SlashDot.org! http://sdm.link/slashdot ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Problem with genserkins
On 3/1/2017 12:09 PM, Andrew wrote: > 2017-02-25 23:46 GMT+02:00 Charles Steinkuehler: > >> Is anyone else doing 5-axis machining with genserkins? >> > > Not exactly machining... but I'm building a 3D printed stepper driven > 6-axis robot arm. So I hope that I'm going to need genserkins soon. > > The AB behavior you describe (if I get it correct) might make some sense. > When you rotate the whole arm and AB angles remain the same in the world > coordinates (that's what you want), the wrist tends to twist impossibly. So > probably this behavior is designed on purpose. Hmm...I see your point, but commanding an AB orientation in world space via gcode would then require knowing the position of the first joint (the base rotation of the whole arm), which is generated from the commanded position via kinematics. In the simple Puma-like serial arm I'm working with this might be possible, but in other arrangements (where more than one axis is rotating around world Z) there are multiple valid solutions, so you can't really infer exact joint positions from the gcode. This really feels like something that either needs to be handled in the machine kinematics, or the gcode needs to be directly controlling the joints (pushing the kinematics off to the CAM system) unless I'm missing something. > I think genserkins can be tweaked to use world AB coordinates. Any pointers for how to do this? I haven't gotten very far through the "gomath" library yet, which is where most of the fun stuff seems to be happening... -- Charles Steinkuehler char...@steinkuehler.net -- Check out the vibrant tech community on one of the world's most engaging tech sites, SlashDot.org! http://sdm.link/slashdot ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Problem with genserkins
2017-02-25 23:46 GMT+02:00 Charles Steinkuehler: > Is anyone else doing 5-axis machining with genserkins? > Not exactly machining... but I'm building a 3D printed stepper driven 6-axis robot arm. So I hope that I'm going to need genserkins soon. The AB behavior you describe (if I get it correct) might make some sense. When you rotate the whole arm and AB angles remain the same in the world coordinates (that's what you want), the wrist tends to twist impossibly. So probably this behavior is designed on purpose. I think genserkins can be tweaked to use world AB coordinates. Best regards, Andrew -- Check out the vibrant tech community on one of the world's most engaging tech sites, SlashDot.org! http://sdm.link/slashdot ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Problem with genserkins
The kinematics in the control have very little or nothing to do with the code interpretation. It is only used to tie the machine components together with the control. The kinematics in the post processor (CAM System) have very little or nothing to do with the control nor the kinematics in the control. The only important relationship between the two is they must match or you don't get correct motion on the machine. This is how it compares to marriage. Two distinct (and sovereign entities) must agree on the course of action to have a positive outcome. You must be very careful in the setup and diligent in maintenance. :) Regarding ownership - my wife and I have a 50/50 relationship - what's mine is hers and what's hers is hers too. As long as I respect her opinion in this matter things progress peacefully and positive. On Wed, Mar 1, 2017 at 7:46 AM, TJoseph Powderlywrote: > i think... > > On 03/01/17 09:16, Charles Steinkuehler wrote: > > On 2/28/2017 5:52 PM, andy pugh wrote: > >> On 26 February 2017 at 22:46, Charles Steinkuehler > >> wrote: > >>> The A and B Axis has no > >>> dependency on the rotation of the base of the robot arm (joint-0). > >>> > >>> Is this the expected behavior? > >> I don't know. > >> > >> I did notice that the C axis value changes when you rotate the base. > >> > >> Have you seen http://linuxcnc.org/docs/devel/html/motion/5-axis- > kinematics.html > >> ? > > Thanks Andy, somehow I missed that document. I'd gathered most of the > > info from reading through some of the 5-axis kinematics code, but it > > still doesn't really address my problem. I think the closest it comes > > is a couple of places where it mentions "These relationships are > > typically used in the CAM post-processor to convert the tool > > orientation vectors to rotation angles". To me that implies the CAM > > needs to have knowledge about the machine and account for the > > kinematics, but it seems like it's far better to do this on the > > machine side (where all the kinematics and dimensions are known). > > > > Perhaps a different way of asking my question: > > > > Given two types of 5-axis machine, one with A and B pivots on the > > spindle, > for the discussion, some vocab :-) > this is 'knucklehead' like a wrist > > and one with A and B pivots on the table, > this is a 'trunnion' config > > would identical > > gcode be expected to produce identical results on these two machines? > i dont think so, but that can be proven if we get two such machines > together with a single part to execute > really, wether the same gcode or different... it doesnt affect the rest > of this thought > > > > On the machine with the pivot on the spindle, operation seems > > straight-forward: Set the A and B angles, then move around in XYZ to > > machine your part. > > > On the machine that pivots the table, however, after setting A and B, > > if you move around in XY, the Z axis will need to be coordinated with > > the part position (since the part is now tilted, moving in X and Y > > also affects the effective Z position). > > > > So is this difference handled in the kinematics, > (i think) the kins have to handle the difference > 'handle' meaning the relations of the joints for machine motion is in > the kins ( which is a description of the joint relationships ) > > in the 'knucklehead' case, the tool axis ( line thru the cutter center > ) is hypothetical ( aint up/down left right inout xyz ish ) > > in the 'trunnion' case the tool axis is simple cartesian and the > workpiece attitude can be aeroplaney pitch yawed > > will AXIS produce the correct visual given the correct kins? dunno, but > it can be tested, but (i think) AXIS is not a proofing tool > > will a vismach animation follow the correct kins? >hmm i DO think so, given that vismach needs a lot of the relations > that the kins would contain >(also I've modeled a few multi axis systems in vismach ) > > will a CAM system produce the ( or 'a' ) good path given the _same_ > kins, well (i think) its broke if it dont > > and, the trunnion is not always just 'posed', often its dynamic. > > (i think) the CAM has to know the same set of kins and react to corner > cases and two-answer problems the same way > > it only works if both the control and path generator have the same idea > how to get to grandmas house > it only works if both the control and path generator have the same kins > > a control and cam system is usually a marriage, > ( doesnt Siemens own NX now? hehehe ) > > or is it expected to > > be handled by post-processing in CAM? > just my 2c > tomp tjtr33 > > > > -- > Check out the vibrant tech community on one of the world's most > engaging tech sites, SlashDot.org! http://sdm.link/slashdot > ___ > Emc-users mailing list > Emc-users@lists.sourceforge.net >
Re: [Emc-users] Problem with genserkins
i think... On 03/01/17 09:16, Charles Steinkuehler wrote: > On 2/28/2017 5:52 PM, andy pugh wrote: >> On 26 February 2017 at 22:46, Charles Steinkuehler >>wrote: >>> The A and B Axis has no >>> dependency on the rotation of the base of the robot arm (joint-0). >>> >>> Is this the expected behavior? >> I don't know. >> >> I did notice that the C axis value changes when you rotate the base. >> >> Have you seen >> http://linuxcnc.org/docs/devel/html/motion/5-axis-kinematics.html >> ? > Thanks Andy, somehow I missed that document. I'd gathered most of the > info from reading through some of the 5-axis kinematics code, but it > still doesn't really address my problem. I think the closest it comes > is a couple of places where it mentions "These relationships are > typically used in the CAM post-processor to convert the tool > orientation vectors to rotation angles". To me that implies the CAM > needs to have knowledge about the machine and account for the > kinematics, but it seems like it's far better to do this on the > machine side (where all the kinematics and dimensions are known). > > Perhaps a different way of asking my question: > > Given two types of 5-axis machine, one with A and B pivots on the > spindle, for the discussion, some vocab :-) this is 'knucklehead' like a wrist > and one with A and B pivots on the table, this is a 'trunnion' config > would identical > gcode be expected to produce identical results on these two machines? i dont think so, but that can be proven if we get two such machines together with a single part to execute really, wether the same gcode or different... it doesnt affect the rest of this thought > > On the machine with the pivot on the spindle, operation seems > straight-forward: Set the A and B angles, then move around in XYZ to > machine your part. > On the machine that pivots the table, however, after setting A and B, > if you move around in XY, the Z axis will need to be coordinated with > the part position (since the part is now tilted, moving in X and Y > also affects the effective Z position). > > So is this difference handled in the kinematics, (i think) the kins have to handle the difference 'handle' meaning the relations of the joints for machine motion is in the kins ( which is a description of the joint relationships ) in the 'knucklehead' case, the tool axis ( line thru the cutter center ) is hypothetical ( aint up/down left right inout xyz ish ) in the 'trunnion' case the tool axis is simple cartesian and the workpiece attitude can be aeroplaney pitch yawed will AXIS produce the correct visual given the correct kins? dunno, but it can be tested, but (i think) AXIS is not a proofing tool will a vismach animation follow the correct kins? hmm i DO think so, given that vismach needs a lot of the relations that the kins would contain (also I've modeled a few multi axis systems in vismach ) will a CAM system produce the ( or 'a' ) good path given the _same_ kins, well (i think) its broke if it dont and, the trunnion is not always just 'posed', often its dynamic. (i think) the CAM has to know the same set of kins and react to corner cases and two-answer problems the same way it only works if both the control and path generator have the same idea how to get to grandmas house it only works if both the control and path generator have the same kins a control and cam system is usually a marriage, ( doesnt Siemens own NX now? hehehe ) > or is it expected to > be handled by post-processing in CAM? just my 2c tomp tjtr33 -- Check out the vibrant tech community on one of the world's most engaging tech sites, SlashDot.org! http://sdm.link/slashdot ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Problem with genserkins
Maybe I can help a little on this subject. In 5-axis machining the 4th and 5th axes are controlled in coordinated moves with the x, y, and z axes. For both configurations, tilting and rotating spindle or tilting and rotating tables, the CAM program must create the correct GCODE for all the axes in each block to control the position of the tool tip as well as its orientation. In that way the tool can, for instance, be kept normal to the surface you are cutting with a flat end mill, or it can be guided into the spaces between the blades of a turbo impeller if you are cutting with a ball nose cutter. Some CAM programs create a position and orientation vector for each block, and the post-processor then converts into GCODE appropriate for your 5-axis machine setup, head or table. Others create it directly based on the machine type you select. If the A and C axes are preset or indexed and then x, y and z axes are moved, then trivkins can be used in a milling machine fitted with two extra axes on the head or the table. For fully coordinated moves to cut general surfaces you need 5-axis kinematics. For robots with rotational joints kinematics are always needed to go from joint to world coordinates. Rudy du Preez -- Check out the vibrant tech community on one of the world's most engaging tech sites, SlashDot.org! http://sdm.link/slashdot ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Problem with genserkins
On 1 March 2017 at 02:16, Charles Steinkuehlerwrote: > > Perhaps a different way of asking my question: > > Given two types of 5-axis machine, one with A and B pivots on the > spindle, and one with A and B pivots on the table, would identical > gcode be expected to produce identical results on these two machines? That would certainly be my expectation, yes. At least for Tool-Centre G-code. Is it possible to jog the Puma sim to a position in World mode, then switch to joint mode, move the base, then switch back to World mode and jog to _exactly_ the same pose and have different XYZABC values? I would rather hope not. -- atp "A motorcycle is a bicycle with a pandemonium attachment and is designed for the especial use of mechanical geniuses, daredevils and lunatics." — George Fitch, Atlanta Constitution Newspaper, 1916 -- Check out the vibrant tech community on one of the world's most engaging tech sites, SlashDot.org! http://sdm.link/slashdot ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Problem with genserkins
The method used to generate the gcode program almost always needs to have knowledge of the kinematics and use that knowledge to calculate the numbers in the gcode program. On Feb 28, 2017 8:20 PM, "Charles Steinkuehler"wrote: > On 2/28/2017 5:52 PM, andy pugh wrote: > > On 26 February 2017 at 22:46, Charles Steinkuehler > > wrote: > >> The A and B Axis has no > >> dependency on the rotation of the base of the robot arm (joint-0). > >> > >> Is this the expected behavior? > > > > I don't know. > > > > I did notice that the C axis value changes when you rotate the base. > > > > Have you seen http://linuxcnc.org/docs/devel/html/motion/5-axis- > kinematics.html > > ? > > Thanks Andy, somehow I missed that document. I'd gathered most of the > info from reading through some of the 5-axis kinematics code, but it > still doesn't really address my problem. I think the closest it comes > is a couple of places where it mentions "These relationships are > typically used in the CAM post-processor to convert the tool > orientation vectors to rotation angles". To me that implies the CAM > needs to have knowledge about the machine and account for the > kinematics, but it seems like it's far better to do this on the > machine side (where all the kinematics and dimensions are known). > > Perhaps a different way of asking my question: > > Given two types of 5-axis machine, one with A and B pivots on the > spindle, and one with A and B pivots on the table, would identical > gcode be expected to produce identical results on these two machines? > > On the machine with the pivot on the spindle, operation seems > straight-forward: Set the A and B angles, then move around in XYZ to > machine your part. > > On the machine that pivots the table, however, after setting A and B, > if you move around in XY, the Z axis will need to be coordinated with > the part position (since the part is now tilted, moving in X and Y > also affects the effective Z position). > > So is this difference handled in the kinematics, or is it expected to > be handled by post-processing in CAM? > > -- > Charles Steinkuehler > char...@steinkuehler.net > > > -- > Check out the vibrant tech community on one of the world's most > engaging tech sites, SlashDot.org! http://sdm.link/slashdot > ___ > Emc-users mailing list > Emc-users@lists.sourceforge.net > https://lists.sourceforge.net/lists/listinfo/emc-users > -- Check out the vibrant tech community on one of the world's most engaging tech sites, SlashDot.org! http://sdm.link/slashdot ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Problem with genserkins
On 2/28/2017 5:52 PM, andy pugh wrote: > On 26 February 2017 at 22:46, Charles Steinkuehler >wrote: >> The A and B Axis has no >> dependency on the rotation of the base of the robot arm (joint-0). >> >> Is this the expected behavior? > > I don't know. > > I did notice that the C axis value changes when you rotate the base. > > Have you seen > http://linuxcnc.org/docs/devel/html/motion/5-axis-kinematics.html > ? Thanks Andy, somehow I missed that document. I'd gathered most of the info from reading through some of the 5-axis kinematics code, but it still doesn't really address my problem. I think the closest it comes is a couple of places where it mentions "These relationships are typically used in the CAM post-processor to convert the tool orientation vectors to rotation angles". To me that implies the CAM needs to have knowledge about the machine and account for the kinematics, but it seems like it's far better to do this on the machine side (where all the kinematics and dimensions are known). Perhaps a different way of asking my question: Given two types of 5-axis machine, one with A and B pivots on the spindle, and one with A and B pivots on the table, would identical gcode be expected to produce identical results on these two machines? On the machine with the pivot on the spindle, operation seems straight-forward: Set the A and B angles, then move around in XYZ to machine your part. On the machine that pivots the table, however, after setting A and B, if you move around in XY, the Z axis will need to be coordinated with the part position (since the part is now tilted, moving in X and Y also affects the effective Z position). So is this difference handled in the kinematics, or is it expected to be handled by post-processing in CAM? -- Charles Steinkuehler char...@steinkuehler.net -- Check out the vibrant tech community on one of the world's most engaging tech sites, SlashDot.org! http://sdm.link/slashdot ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Problem with genserkins
On 26 February 2017 at 22:46, Charles Steinkuehlerwrote: > The A and B Axis has no > dependency on the rotation of the base of the robot arm (joint-0). > > Is this the expected behavior? I don't know. I did notice that the C axis value changes when you rotate the base. Have you seen http://linuxcnc.org/docs/devel/html/motion/5-axis-kinematics.html ? -- atp "A motorcycle is a bicycle with a pandemonium attachment and is designed for the especial use of mechanical geniuses, daredevils and lunatics." — George Fitch, Atlanta Constitution Newspaper, 1916 -- Check out the vibrant tech community on one of the world's most engaging tech sites, SlashDot.org! http://sdm.link/slashdot ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Problem with genserkins
On 2/25/2017 3:46 PM, Charles Steinkuehler wrote: > > Further investigation shows that the A and B coordinates are being > applied to something relative to the end of the robot arm. Regardless > of the XYZ position of the arm, A and B moves always do the same thing > relative to the robot arm. I would have thought the A and B > coordinates would be relative to the work-piece, just like XYZ, or is > that not how it works? > > Anyway, either I'm confused about 5-axis machining, there's something > odd with genserkins, or both. Any suggestions on where to look for > enlightenment (other than the genserkins code which I'm already > reviewing) would be appreciated! > > Is anyone else doing 5-axis machining with genserkins? I have further tested this behavior using both my physical robot configuration and the Puma-560 sim configuration. Both behave the same way, with the A and B axis values/positions unaffected by the overall rotation of the robot arm (Joint-0, at the base of the arm). This seems like a pretty basic issue, so I suspect either my understanding of how the A and B axis should work is incorrect or there aren't very many people using genserkins with 5-axis movements. To reproduce: * Launch the Puma-560 config (sim -> axis -> vismach -> puma -> puma560) which uses genserkins * Deassert ESTOP and power-on * Home all * Move to a handy AB axis setting, I used: G0 A180 B45 * Note XYZAB positions * Go back to joint coordinates ($) * Move joint-0 a substantial amount (I moved it to ~ 45 deg) * Return to world coordinates ($) * Note that XYZ positions have changed, but A and B positions remain at A=180, B=45 I also tested with the Puma sim config (which uses pumakins instead of genserkins) and it behaves the same way: The A and B Axis has no dependency on the rotation of the base of the robot arm (joint-0). Is this the expected behavior? -- Charles Steinkuehler char...@steinkuehler.net signature.asc Description: OpenPGP digital signature -- Check out the vibrant tech community on one of the world's most engaging tech sites, SlashDot.org! http://sdm.link/slashdot___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
[Emc-users] Problem with genserkins
I am having some issues with genserkins running a robot arm (this is the ST R-17 I brought with me to Wichita running LinuxCNC with joints-axis running on Debian Wheezy with RTAI). Coordinated moves in XYZ seem to work as expected. All the joints working together to keep the end of the arm moving properly in XYZ, with the tool perpendicular to the XY plane. The problem comes when I try to use the A and B axis for 5-axis movement. My first problem was that A moves pivot around the Y axis and B moves pivot around X (at least in what I've chosen as the default pose for the robot). I thought this was something wrong with my configuration, so I double and triple-checked everything (it's super easy to get confused about the reference frame as you go from joint to joint), but that all looks good. Then I tried rotating the arm around the base by 90 degrees, and suddenly A pivots around X and B pivots around Y. Further investigation shows that the A and B coordinates are being applied to something relative to the end of the robot arm. Regardless of the XYZ position of the arm, A and B moves always do the same thing relative to the robot arm. I would have thought the A and B coordinates would be relative to the work-piece, just like XYZ, or is that not how it works? Anyway, either I'm confused about 5-axis machining, there's something odd with genserkins, or both. Any suggestions on where to look for enlightenment (other than the genserkins code which I'm already reviewing) would be appreciated! Is anyone else doing 5-axis machining with genserkins? -- Charles Steinkuehler char...@steinkuehler.net -- Check out the vibrant tech community on one of the world's most engaging tech sites, SlashDot.org! http://sdm.link/slashdot ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
andy pugh wrote: It may be that the joint lengths in the DH parameters are slightly wrong. It is less likely to be the stepgen scales, but that would have a similar effect. I checked the d-h parameters many many times and they should be correct. Also if I don't understand why in world mode the movement in direction positive of x correspond a movement negative of my robot. I tried to invert some pin but the situation has worsened: the movement on x aren't on x direction! -- Cloud Services Checklist: Pricing and Packaging Optimization This white paper is intended to serve as a reference, checklist and point of discussion for anyone considering optimizing the pricing and packaging model of a cloud services business. Read Now! http://www.accelacomm.com/jaw/sfnl/114/51491232/ ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 6 December 2011 12:48, Francesca Sca fancy_...@yahoo.it wrote: I checked the d-h parameters many many times and they should be correct. I might still be tempted to tune them. (ie, forget the science, just make small changes and see what happens). How far out are the distances? Also if I don't understand why in world mode the movement in direction positive of x correspond a movement negative of my robot. I tried to invert some pin but the situation has worsened: the movement on x aren't on x direction! Changing the direction pins will only change the direction that the motors turn, which will really mess things up. I think that, again, to swap the X-direction you would need to change DH parameters. (negative angles?) It might be easier just to sit at the other side of the robot :-) -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- Cloud Services Checklist: Pricing and Packaging Optimization This white paper is intended to serve as a reference, checklist and point of discussion for anyone considering optimizing the pricing and packaging model of a cloud services business. Read Now! http://www.accelacomm.com/jaw/sfnl/114/51491232/ ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Andy pugh wrote: I might still be tempted to tune them. (ie, forget the science, just make small changes and see what happens). How far out are the distances? The distances are far5 or 6 cm more on z and 4 or 5 cm less on x and y!! And then the movement aren't linearfor example the movement on z isn't vertical...! In according with the D-H setted for PUMA robot, I calculeted these for my robot Armdroid 1: setp genserkins.A-0 0 setp genserkins.A-1 0 setp genserkins.A-2 Lenght of upper arm (in millimeter) setp genserkins.A-3 0 setp genserkins.A-4 0 setp genserkins.A-5 0 setp genserkins.ALPHA-0 0 setp genserkins.ALPHA-1 1.570796326 setp genserkins.ALPHA-2 0 setp genserkins.ALPHA-3 1.570796326 setp genserkins.ALPHA-4 -1.570796326 setp genserkins.ALPHA-5 1.570796326 setp genserkins.D-0 Height of the base (mm) setp genserkins.D-1 0 setp genserkins.D-2 0 setp genserkins.D-3 Lenght of forearm (mm) setp genserkins.D-4 0 setp genserkins.D-5 wirst -- Cloud Services Checklist: Pricing and Packaging Optimization This white paper is intended to serve as a reference, checklist and point of discussion for anyone considering optimizing the pricing and packaging model of a cloud services business. Read Now! http://www.accelacomm.com/jaw/sfnl/114/51491232/ ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Andy pugh wrote: I think the HAL will work, I don't know if the function of that code is correct. If it doesn't work, then what it needs is some of the signals inverting (scale by -1) before going in to the offset function. I set the offset function like you have suggested me and I tried every combinations of signals (parport.0.pin-X-out-invert) but I have always 2 rotation or 2 elevation and ever 1 rotation and 1 elevation. I tried also to set -1 in the section SCALE in the ini file. Which could be the problem?? -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 5 December 2011 09:38, Francesca Sca fancy_...@yahoo.it wrote: I set the offset function like you have suggested me and I tried every combinations of signals (parport.0.pin-X-out-invert) but I have always 2 rotation or 2 elevation and ever 1 rotation and 1 elevation. I tried also to set -1 in the section SCALE in the ini file. Which could be the problem?? The problem is that I didn't explain properly. I was meaning that you might need to pass one or both the position signals though a HAL scale function with a value of -1 to get the required effect (this means that the offset becomes subtract rather than add) http://www.linuxcnc.org/docview/html/man/man9/scale.9.html Can you analyse what needs to happen to make the hand do what you want? ie, with the original one-to-one joint mapping, manually jog the hand into (0,0), (90, 0), (-90, 0), (0, 90, 0, -90) positions in (elevation, rotation) and note down the motor-position-cmd values which correspond to each position? There is only so much we can do by guessing. -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Andy pugh wrote: The problem is that I didn't explain properly. I was meaning that you might need to pass one or both the position signals though a HAL scale function with a value of -1 to get the required effect (this means that the offset becomes subtract rather than add) http://www.linuxcnc.org/docview/html/man/man9/scale.9.html So I should use another function scale with a value -1 to have both the moviment. How I should write the commands and then link to the function offset? Can you analyse what needs to happen to make the hand do what you want? ie, with the original one-to-one joint mapping, manually jog the hand into (0,0), (90, 0), (-90, 0), (0, 90, 0, -90) positions in (elevation, rotation) and note down the motor-position-cmd values which correspond to each position? I saw the motor-position-cmd value in the section Show Hal configuration and to position (90, 0) corrispond the same value 90 and 0 for the motor-position-cmd and so on for the other position -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Andy pugh wrote: How I should write the commands and then link to the function offset? Just like any other HAL function, loadrt / addf / net. http://www.linuxcnc.org/docview/html/hal_basic_hal.html ok I tried with these lines for see what happen: loadrt scale count=1 loadrt offset count=2 add scale.0 servo-thread setp scale.0.gain -1 addf offset.0.update-output servo-thread addf offset.1.update-output servo-thread addf offset.0.update-feedback servo-thread addf offset.1.update-feedback servo-thread net elevation axis.4.motor-pos-cmd = scale.0.in net scal scale.0.out = offset.0.in offset.1.offset net rotation axis.5.motor-pos-cmd = offset.1.in offset.0.offset net mot1 offset.0.out = stepgen.4.position-cmd net mot2 offset.1.out = stepgen.5.position-cmd net elev-fb-in offset.0.fb-in = stepgen.4.position-fb net elev-fb-out offset.0.fb-out axis.4.motor-pos-fb net rot-fb-in offset.1.fb-in = stepgen.5.position-fb net rot-fb-out offset.1.fb-out axis.5.motor-pos-fb . Nothing has happened, of course I must change something...but I'm going in the right way?? -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 5 December 2011 13:51, Francesca Sca fancy_...@yahoo.it wrote: add scale.0 servo-thread addf net elevation axis.4.motor-pos-cmd = scale.0.in net scal scale.0.out = offset.0.in offset.1.offset That has the same effect as inverting axis.4. I think you need to break the symmetry, so net elevation axis.4.motor-pos-cmd = scale.0.in offset.0.in net scal scale.0.out = offset.1.offset Is more likely to work. (offset.0 gets the normal value, offset.1 gets the negated value). You might need two scale functions, then, combined with inverting the stepper directions you have 16 combinations to play with. One of them ought to work :-) -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
You might need two scale functions, then, combined with inverting the stepper directions you have 16 combinations to play with. One of them ought to work :-) I have changed the command how you suggest me and I have got what I wanted with the first combination!! I'm very lucky!!! :p I would like to ask you some help with the my last problem. When I use the world mode (inverse kinematics) my robot isn't accurate. For example if I write G01 z100, the robot doesn't move 100mm on z but every time more mm. The same thing happens on x and y ( actually a few mm less). What could be the problem? input_scale on ini file? or what? The genserkins module is a generic module, so the equations of inverse kinematic should work correctly. -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 5 December 2011 14:34, Francesca Sca fancy_...@yahoo.it wrote: I would like to ask you some help with the my last problem. When I use the world mode (inverse kinematics) my robot isn't accurate. For example if I write G01 z100, the robot doesn't move 100mm on z but every time more mm. The same thing happens on x and y ( actually a few mm less). What could be the problem? It may be that the joint lengths in the DH parameters are slightly wrong. It is less likely to be the stepgen scales, but that would have a similar effect. -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Andy pugh wrote: I think that needs a custom HAL component, using comp. Part of the problem is that you need to get the feedback back the other way. It is just possible that you might be able to do it all with two offset functions: http://www.linuxcnc.org/docview/html/man/man9/offset.9.html loadrt offset count=2 … addf offset.0.update-output servo-thread addf offset.1.update-output servo-thread addf offset.0.update-feedback servo-thread addf offset.1.update-feedback servo-thread … net elevation axis.4.motor-pos-cmd = offset.0.in offset.1.offset net rotation axis.5.motor-pos-cmd = offset.1.in offset.0.offset net mot1 offset.0.out = stepgen.4.position-cmd net mot2 offset.1.out = stepgen.5.position-cmd net elev-fb-in offset.0.fb-in = stepgen.4.position-fb net elev-fb-out offset.0.fb-out axis.4.motor-pos-fb net elev-fb-in offset.1.fb-in = stepgen.5.position-fb net elev-fb-out offset.1.fb-out axis.5.motor-pos-fb With appropriate setting/clearing of the parport invert bits on the direction pins (see the previous message), there is a fair chance that might work. So, I should just add these command to my file .hal? Right? Or I should compilate a particular module? And then I can link without problem stepgen to parport pins just with: net stepgen.4.step = parport.0.pin-09-out net stepgen.4.dir = parport.0.pin-08-out net stepgen.5.step = parport.0.pin-07-out net stepgen.5.dir = parport.0.pin-06-out In this way I can combine the two motor to have the rotation and the elevation of wirst? -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 3 December 2011 12:40, Francesca Sca fancy_...@yahoo.it wrote: loadrt offset count=2 So, I should just add these command to my file .hal? Right? Or I should compilate a particular module? That is something to try in the HAL file. It sounds like you are not 100% familiar with HAL yet, and I think you are going to need to be, especially as I doubt that my code is accurate enough to work first time. You might want to read http://www.linuxcnc.org/docs/HAL_User_Manual.pdf Or at least the shorter introduction here: http://www.linuxcnc.org/docview/html/hal_basic_hal.html (There is documentation in French, German and Spanish too, but I don't know of any Italian. Of course, if you want to translate it or us….) And then I can link without problem stepgen to parport pins just with: net stepgen.4.step = parport.0.pin-09-out net stepgen.4.dir = parport.0.pin-08-out net stepgen.5.step = parport.0.pin-07-out net stepgen.5.dir = parport.0.pin-06-out In this way I can combine the two motor to have the rotation and the elevation of wirst? Possibly. It might work, but will probably need some adjustment. -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
2011/12/3 Francesca Sca fancy_...@yahoo.it: Or: Motor.4-cmd = joint.4-cmd + joint.5-cmd Motor.5-cmd = joint.4-cmd - joint.5-cmd To get correct feedback value, use last 2 equations and derive feedback positions: joint.4-fb = (motor.4-fb + motor.5-fb) / 2 joint.5-fb = (motor.4-fb - motor.5-fb) / 2 I think that this can easily be done with custom HAL component with 4 float inputs (for joint-cmd and motor-fb values) and 4 float outputs (for motor-cmd and joint-fb). You can me explain better what you suggest me? Where and how I should add these command? I suggest that You write Your own HAL component, like offset component or any other component, that is loaded in HAL with loadrt command. How to learn doing it? 1) Get source code of EMC2: http://wiki.linuxcnc.org/emcinfo.pl?Installing_EMC2#Getting_the_source_with_git 2) Go to ~/emc2-dev/src/hal/components folder, where are source files of different HAL components and open one of them (and save with different name). 3) Take each line one by one and try to understand, what do they mean. Sum2 is good example - it is very short, but it has lines that create floating input pins, parameters (which You do not need, but it is good example that shows the code to create them), floating output pins and also function part, where You should put in the math formulas, for example, those that I suggested as they are, modified or whatever that works for You. Here is what pins are created and what are their respective names: http://www.linuxcnc.org/docview/devel/html/man/man9/sum2.9.html Compare it with the source file of the component and learn, how those things are done. That will give You understanding, how to create Your own realtime component that can take care of different tasks. This is the way I learned to tweak EMC2. Usually I modify a component in a way that I think it should work, then try to comp--install it and then I start fixing all the mistakes I have made - I am no programmer, so I tend to make many syntax errors. Andy pugh suggested to use the component offset to have the rotation and elevation of wirst using ate the same time the two motors.. With all due respect to Andy, I did not have time to go through his suggested solution in HAL. AFAIK he knows HAL very well, so that solution should work well. It is Your choice, which path to take. Viesturs -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 3 December 2011 21:39, Viesturs Lācis viesturs.la...@gmail.com wrote: With all due respect to Andy, I did not have time to go through his suggested solution in HAL. AFAIK he knows HAL very well, so that solution should work well. I think the HAL will work, I don't know if the function of that code is correct. If it doesn't work, then what it needs is some of the signals inverting (scale by -1) before going in to the offset function. -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
2011/12/1 Francesca Sca fancy_...@yahoo.it: Viesturs wrote: It is more than just simple: put 2 stepgens in the receiving end of signal. net J0pos-cmd axis.0.motor-pos-cmd = stepgen.0.position-cmd stepgen.1.position-cmd Ok, I can do in this way, But I should change something also to stepgen.0.step or stepgen.0.dir? I don't konw. I said that because the combination of two motors should give the rotation of wirst: net J0pos-cmd axis.0.motor-pos-cmd = stepgen.0.position-cmd stepgen.1.position-cmd but either motor should give alone also the up and down of wirst. For this moviment I should set another stepgen? but then i don't know how set stepgen.N.dir and stepgen.N.step -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 2 December 2011 10:16, Francesca Sca fancy_...@yahoo.it wrote: I don't konw. I said that because the combination of two motors should give the rotation of wirst: Do you have a picture/diagram? I can imagine designs where two motors in parallel drive a wrist joint, in which case you do not have a serial kinematics, but a part-serial, part-parallel one. but either motor should give alone also the up and down of wirst. For this moviment I should set another stepgen? but then i don't know how set stepgen.N.dir and stepgen.N.step You don't set the step/dir, those are the outputs, you just need to connect them to physical output pins to drive the stepgen. -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Andy pugh wrote: Do you have a picture/diagram? I can imagine designs where two motors in parallel drive a wrist joint, in which case you do not have a serial kinematics, but a part-serial, part-parallel one. http://mecatronicaeajm.blogspot.com/2010_05_01_archive.html For the roll of the wirst, the two side gears must move in opposite direction and this is realized by the moviment of two motors. For the pitch just the moviment of a motor and thus a lateral gear plus frontal gear. You don't set the step/dir, those are the outputs, you just need to connect them to physical output pins to drive the stepgen. ok but I should use 2 physical output pins to drive both stepgen.4.dir , stepgen.4.step and stepgen.5.dir stepgen.5.step. How I can realize this? -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 2 December 2011 11:21, Francesca Sca fancy_...@yahoo.it wrote: http://mecatronicaeajm.blogspot.com/2010_05_01_archive.html For the roll of the wirst, the two side gears must move in opposite direction and this is realized by the moviment of two motors. For the pitch just the moviment of a motor and thus a lateral gear plus frontal gear. Hmm, yes. I see the problem. It's quite a neat mechanism, you turn both gears the same direction for up-down and in different directions for rotate. The solution is probably to abstract the two movements into basic angles as far as the DH parameters go, so that you have an elevation and a rotation angle as numbers in the joint.N.pos-cmd pins, then do some mathematics in HAL to convert those to stepgen positions using some simple maths in HAL. I think that stepgen.4 needs to be joint.4 - joint.5 and stepgen.5 needs to be joint.5 - joint.4 (or something a bit like that anyway) There is no subtraction in HAL, you need to sum and scale by -1 I think. It might be simpler to write a very simple custom HAL component that takes the two angle values and converts them into two motor positions. (like a very small 2-axis kinematics file). Alternatively, as the Armdroid is very simple, perhaps genserkins is overkill, and it would be simpler to modify pumakins to match your robot? -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Hmm, yes. I see the problem. It's quite a neat mechanism, you turn both gears the same direction for up-down and in different directions for rotate. The solution is probably to abstract the two movements into basic angles as far as the DH parameters go, so that you have an elevation and a rotation angle as numbers in the joint.N.pos-cmd pins, then do some mathematics in HAL to convert those to stepgen positions using some simple maths in HAL. I think that stepgen.4 needs to be joint.4 - joint.5 and stepgen.5 needs to be joint.5 - joint.4 (or something a bit like that anyway) There is no subtraction in HAL, you need to sum and scale by -1 I think. It might be simpler to write a very simple custom HAL component that takes the two angle values and converts them into two motor positions. (like a very small 2-axis kinematics file). Hmm...I don't understand very well what this means. You suggest me to create an HAL component or some maths in HAL to pass the Joints pos values (calculated by genserkins?) to stepgen 4 and 5. Right? This don't seems very easy...at least for me! But then how I should do to link stepgen to physical pin of parallel port to move at the same time the two motor? I don't understand how to link halparport pin to both stepgen. -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 2 December 2011 13:52, Francesca Sca fancy_...@yahoo.it wrote: Hmm...I don't understand very well what this means. You suggest me to create an HAL component or some maths in HAL to pass the Joints pos values (calculated by genserkins?) to stepgen 4 and 5. Right? Yes. Genserkins rather assumes that the motor position directly controls the joint position. With your machine this is not the case. This don't seems very easy...at least for me! It isn't any harder than other things you have already done. The first thing to work out is how the two stepgen positions correlate to wrist positions. You can figure that out by jogging in joint mode while looking at the stepgen-pos-cmd pins in Machine-Show HAL config (use the Watch tab, as the other tab doesn't update the values in real time). But then how I should do to link stepgen to physical pin of parallel port to move at the same time the two motor? I don't understand how to link halparport pin to both stepgen. You want to link each stepgen to one step and one direction pin each. We were confused earlier. -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Andy pugh wrote: It isn't any harder than other things you have already done. The first thing to work out is how the two stepgen positions correlate to wrist positions. You can figure that out by jogging in joint mode while looking at the stepgen-pos-cmd pins in Machine-Show HAL config (use the Watch tab, as the other tab doesn't update the values in real time). When I looking at stepgen-pos-cmd pins in Show HAL config, I see only a series of numbers. You want to link each stepgen to one step and one direction pin each. We were confused earlier. So I can link each stepgen to only one step and one direction pin. Thus how I can move simultaneously the two motors in a different directions for have the rotation of wirst and in the same directions for have the up and down of wirst? This isn't possible setting appropriately pin and signal (also only in forwards kinematic)? -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 2 December 2011 16:33, Francesca Sca fancy_...@yahoo.it wrote: When I looking at stepgen-pos-cmd pins in Show HAL config, I see only a series of numbers. Yes. What did you expect to see? So I can link each stepgen to only one step and one direction pin. No, you can link each stepgen to as many parallel port pins as you want, but I don't think that will have the required effect. If you only wanted to move the hand up and down, or rotate it, then it would be a simple case of wiring one stepgen to both motors (And it would only require you to change the polarity of one of the direction pins to swap between elevation and rotation). Thus how I can move simultaneously the two motors in a different directions for have the rotation of wirst and in the same directions for have the up and down of wirst? If you only want up and down, and no rotation, then it could be as simple as wiring the same parallel port pins to two stepper drives. However, that removes the option of adding wrist-rotate later. Assuming that the wrist is joint j and you want the two wrist motors to be controlled by stepgen k, and that the two stepgens are m and n and the parport pins to be used are a, b, c and d... net wrist axis.j.motor-pos-cmd = stepgen.k.pos-cmd net wrist-step stepgen.k.step = parport.0.pin-a-out parport.0.pin-c-out net wrist-dir stepgen.k.dir = parport.0.pin-b-out parport.0.pin-d-out That links the joint position to one stepgen amd directs the step/dir signals to the parport. You can now try the various combinations of setp parport.0.pin-b-invert 0 setp parport.0.pin-d-invert 0 or setp parport.0.pin-b-invert 1 setp parport.0.pin-d-invert 0 or setp parport.0.pin-b-invert 0 setp parport.0.pin-d-invert 1 or setp parport.0.pin-b-invert 1 setp parport.0.pin-d-invert 1 You should find that two combinations rotate the wrist and two elevate it, with different directions corresponding to positive and negative moves. I still think it seems a shame not to use all the degrees of freedom though. -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Andy pugh wrote: I still think it seems a shame not to use all the degrees of freedom though. Infact I don't want loose a DOF. I would like to find a solution for have in the joint mode both the rotation of the wirst and the up and down, setting in the right way stepgen and pins. There are this solution? Or I should create some particular components? -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 2 December 2011 17:35, Francesca Sca fancy_...@yahoo.it wrote: Infact I don't want loose a DOF. I would like to find a solution for have in the joint mode both the rotation of the wirst and the up and down, setting in the right way stepgen and pins. There are this solution? Or I should create some particular components? I think that needs a custom HAL component, using comp. Part of the problem is that you need to get the feedback back the other way. It is just possible that you might be able to do it all with two offset functions: http://www.linuxcnc.org/docview/html/man/man9/offset.9.html loadrt offset count=2 … addf offset.0.update-output servo-thread addf offset.1.update-output servo-thread addf offset.0.update-feedback servo-thread addf offset.1.update-feedback servo-thread … net elevation axis.4.motor-pos-cmd = offset.0.in offset.1.offset net rotation axis.5.motor-pos-cmd = offset.1.in offset.0.offset net mot1 offset.0.out = stepgen.4.position-cmd net mot2 offset.1.out = stepgen.5.position-cmd net elev-fb-in offset.0.fb-in = stepgen.4.position-fb net elev-fb-out offset.0.fb-out axis.4.motor-pos-fb net elev-fb-in offset.1.fb-in = stepgen.5.position-fb net elev-fb-out offset.1.fb-out axis.5.motor-pos-fb With appropriate setting/clearing of the parport invert bits on the direction pins (see the previous message), there is a fair chance that might work. Note this was written from memory, any or all pin names might be wrong, and the signal names might be in use, and it simply might not work. -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
2011/12/2 andy pugh bodge...@gmail.com: On 2 December 2011 17:35, Francesca Sca fancy_...@yahoo.it wrote: Infact I don't want loose a DOF. I would like to find a solution for have in the joint mode both the rotation of the wirst and the up and down, setting in the right way stepgen and pins. There are this solution? Or I should create some particular components? I think that needs a custom HAL component, using comp. Part of the problem is that you need to get the feedback back the other way. Thanks, that sketch was useful, I could not picture the solution, but, when I saw it, then it was like dooh, so simple... I think I figured out the solution: For genserkins: joint 4 - wrist up/down joint 5 - wrist rotate set correct DH parameters for that to happen (disregard both motors, take into account only kinematics of arms - the joints, allignement of rotation axes of joints) Now the joint positions need to be transfered to motor positions. Make sure to match the direction of positive rotation for both motors to positive movement of up/down joint, respectively, when both are moving in positive direction, arm is going up. Motor 4 is up + rotate Motor 5 is up - rotate Or: Motor.4-cmd = joint.4-cmd + joint.5-cmd Motor.5-cmd = joint.4-cmd - joint.5-cmd To get correct feedback value, use last 2 equations and derive feedback positions: joint.4-fb = (motor.4-fb + motor.5-fb) / 2 joint.5-fb = (motor.4-fb - motor.5-fb) / 2 I think that this can easily be done with custom HAL component with 4 float inputs (for joint-cmd and motor-fb values) and 4 float outputs (for motor-cmd and joint-fb). Viesturs -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Andy pugh wrote: What I was suggesting was adding: world-u = joint[6]; world-v = joint[7]; world-w = joint[8]; In the forward kins, and joint[6] = world-u; joint[7] = world-v; joint[8] = world-w; In the inverse kins. and then controlling the gripper with U, V or W in the G-code and linking that motor to axis.{6/7/8}.motor-pos-cmd in the HAL. I don't know for sure that this would work, and it means that you cant have a robot with more than 6 elbows I tried to do how you have suggest me but when i recompiled genserkins.c many errors appear! I read that maybe the command sudo comp --install genserkins.c could be incorrect. I should rebuilt with make command. This is correct? you can me explain the complete command that I should use? I have another problem with axis and joints. In the puma configuration the wirst can rotate and go up and down. Two different motor (for example A and B) realize these movements. In my robot also the wirst can rotate and go up and down but the motor A realizes the rotation of wirst; A and B together realize the up and down. There is a way for change genserkins and consider this difference? -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 1 December 2011 14:58, Francesca Sca fancy_...@yahoo.it wrote: I tried to do how you have suggest me but when i recompiled genserkins.c many errors appear! What errors? I have another problem with axis and joints. In the puma configuration the wirst can rotate and go up and down. Two different motor (for example A and B) realize these movements. In my robot also the wirst can rotate and go up and down but the motor A realizes the rotation of wirst; A and B together realize the up and down. A, B and C control the angle of the end-effector, you don't have an A motor, you have joint motors with numerical indices. (joint.7 for example) Genserkins should be adaptable to any wrist motor arrangement. -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Andy pugh wrote: What errors? the same error of this user http://www.mail-archive.com/emc-developers@lists.sourceforge.net/msg03964.html A, B and C control the angle of the end-effector, you don't have an A motor, you have joint motors with numerical indices. (joint.7 for example) Genserkins should be adaptable to any wrist motor arrangement. Yes, of coursemotor A and B were only an example. In my case the joint motors 3 and 4 control together the up and down of the wirst and only joint motor 3 the rotation of wirst. How can I consider this in genserkins? I should change D-H parameters? or I should make some change in hal? -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 1 December 2011 15:33, Francesca Sca fancy_...@yahoo.it wrote: the same error of this user http://www.mail-archive.com/emc-developers@lists.sourceforge.net/msg03964.html I take it that the changes don't work? Those are all warnings, and the new version of the kensrkins module is created and installed (cp genserkins.ko /usr/realtime-2.6.32-122-rtai/modules/emc2/ at the end) Yes, of coursemotor A and B were only an example. In my case the joint motors 3 and 4 control together the up and down of the wirst and only joint motor 3 the rotation of wirst. How can I consider this in genserkins? I should change D-H parameters? or I should make some change in hal? Possibly a bit of both. The joints are numbered from the base to the tip, in the physical sequence of the robot. However, you can pass the joint-pos-cmd value in HAL to any stepgen or PWM that you want to, though that is an easy route to confusion. The DH parameters need to be correct for your particular robot. -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Andy pugh wrote: Possibly a bit of both. The joints are numbered from the base to the tip, in the physical sequence of the robot. However, you can pass the joint-pos-cmd value in HAL to any stepgen or PWM that you want to, though that is an easy route to confusion. You can explain me better this? To the rotation of wirst should corrispond to the moviment of 2 stepper motor. This doesn't create problem with the inverse kinematics of genserkins? -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 1 December 2011 16:59, Francesca Sca fancy_...@yahoo.it wrote: You can explain me better this? To the rotation of wirst should corrispond to the moviment of 2 stepper motor. This doesn't create problem with the inverse kinematics of genserkins? As long as it is a true serial kinematics, and is correctly described by the DH parameters, it ought to work. However, you are more of an expert than me on Genserkins, you are actually using it... -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
2011/12/1 Francesca Sca fancy_...@yahoo.it: Andy pugh wrote: What errors? the same error of this user http://www.mail-archive.com/emc-developers@lists.sourceforge.net/msg03964.html It turned out that genserkins was too complicated for comp, so that is why it is complaining about these errors. You already mentioned, what to do: Run make command (cd to src folder at first). Viesturs -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Andy Pugh wrote: However, you are more of an expert than me on Genserkins, you are actually using it... I am not so expert Possibly a bit of both. The joints are numbered from the base to the tip, in the physical sequence of the robot. However, you can pass the joint-pos-cmd value in HAL to any stepgen or PWM that you want to, though that is an easy route to confusion. How I can pass a joint-pos-cmd value to stepgen and so to two different motors? For example I could use this net J0pos-cmd axis.0.motor-pos-cmd = stepgen.0.position-cmd and the other motor? -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
2011/12/1 Francesca Sca fancy_...@yahoo.it: How I can pass a joint-pos-cmd value to stepgen and so to two different motors? It is more than just simple: put 2 stepgens in the receiving end of signal. net J0pos-cmd axis.0.motor-pos-cmd = stepgen.0.position-cmd stepgen.1.position-cmd Viesturs -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Viesturs wrote: It is more than just simple: put 2 stepgens in the receiving end of signal. net J0pos-cmd axis.0.motor-pos-cmd = stepgen.0.position-cmd stepgen.1.position-cmd Ok, I can do in this way, But I should change something also to stepgen.0.step or stepgen.0.dir? -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
2011/12/1 Francesca Sca fancy_...@yahoo.it: Viesturs wrote: It is more than just simple: put 2 stepgens in the receiving end of signal. net J0pos-cmd axis.0.motor-pos-cmd = stepgen.0.position-cmd stepgen.1.position-cmd Ok, I can do in this way, But I should change something also to stepgen.0.step or stepgen.0.dir? Why? Viesturs -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Andy pugh wrote: I think that the easiest solution might be to use M67 to send position commands out of the G-code to a HAL pin, and link that direct to a stepgen in HAL. I have the version 2.4.6. This could be a problem with that command? However the command is M67 E Q . You can me explain better what are E and Q? Alternatively, it is probably possible to modify genserkins to pass-through UV and W in the same way as trivkins does. (line 357 onwards for forward kins, I can't immediately see where to do it for inverse kins) You mean that for example if I want to exclude the axis C from genserkins I should change this line: world-c = rpy.y * 180 / PM_PI to world-u = rpy.y * 180 / PM_PI ( and so for every line where C appears!) In this way genserkins calculates the kinematics using the axis U and not C. Am I right? With this change Could I control C separatly from kinematics? -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
2011/11/18 Francesca Sca fancy_...@yahoo.it: I have the version 2.4.6. This could be a problem with that command? However the command is M67 E Q . You can me explain better what are E and Q? http://www.linuxcnc.org/docview/html/gcode_main.html#sec:M67-Analog-Output You mean that for example if I want to exclude the axis C from genserkins I should change this line: world-c = rpy.y * 180 / PM_PI to world-u = rpy.y * 180 / PM_PI ( and so for every line where C appears!) In this way genserkins calculates the kinematics using the axis U and not C. Am I right? With this change Could I control C separatly from kinematics? The formula suggests that it is a rotation angle, which I do not think is what the gripper fingers do. RPY are meant to be roll-pitch-yaw angles, which are very close to Euler angles: http://en.wikipedia.org/wiki/Euler_angles IMHO Substituting C with U will screw it up. If You really want to do it in kinematics rather than HAL, then adding trivial kinematics for U (and also V and W), with these lines, where appropriate (inverse and forward kins), should be easier: world-u = joints[6] joints[6] = world-u Viesturs -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 18 November 2011 10:51, Francesca Sca fancy_...@yahoo.it wrote: I think that the easiest solution might be to use M67 to send position commands out of the G-code to a HAL pin, and link that direct to a stepgen in HAL. I have the version 2.4.6. This could be a problem with that command? Yes, it doesn't work in 2.4, but has been fixed in 2.5. Alternatively, it is probably possible to modify genserkins to pass-through UV and W in the same way as trivkins does. (line 357 onwards for forward kins, I can't immediately see where to do it for inverse kins) You mean that for example if I want to exclude the axis C from genserkins I should change this line: world-c = rpy.y * 180 / PM_PI to world-u = rpy.y * 180 / PM_PI ( and so for every line where C appears!) No, I think that might be a bad idea. C is part of the end-pose of the arm, and I would hesitate to interfere with it. What I was suggesting was adding: world-u = joint[6]; world-v = joint[7]; world-w = joint[8]; In the forward kins, and joint[6] = world-u; joint[7] = world-v; joint[8] = world-w; In the inverse kins. and then controlling the gripper with U, V or W in the G-code and linking that motor to axis.{6/7/8}.motor-pos-cmd in the HAL. I don't know for sure that this would work, and it means that you cant have a robot with more than 6 elbows -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
2011/11/16 Francesca Sca fancy_...@yahoo.it: Andrew wrote: If you want to completely control the fingers angle, you can assign another axis for them. It might be W if you already have XYZABC. I guess, you should add the axis to your HAL file and genserkins. It requires no kinematic transformation, just add the direct connection. My axis C is associated to the opening and closing of fingers. So I should using only 5 axes for the genserkins module and exclude the last one C to the kinematic trasformation? Could be correct? It is possible using genserkins for only 5 axes? What I should change? Genserkins will treat C as a rotary axis. It is binded into all those matrix conversions, jacobian functions and other stuff that I do not fully understand. IMHO, if You want to control the gripper, it should be anything but XYZABC. I agree with Andrew that adding U, V or W might be the way to go. On the other hand, adding that to genserkins does not seem very easy (at least for me). You could do that in HAL with limit3 component directly feeding the position to stepgen. The question is - how to tell limit3, what is requested end position, where it should go. It depends on how You intend to control the gripper - just a simple open/close operation, or do You want to control, how much it opens up. Viesturs -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Viesturs wrote: Genserkins will treat C as a rotary axis. It is binded into all those matrix conversions, jacobian functions and other stuff that I do not fully understand. IMHO, if You want to control the gripper, it should be anything but XYZABC. I agree with Andrew that adding U, V or W might be the way to go. On the other hand, adding that to genserkins does not seem very easy (at least for me). I have read a post of Alex Joni (the developer of genserkins) where he said that this module works at least 6 axis. If the machine has fewer, I need to set the others as dummy. So the solution could be using genserkins for 5 axis and 1 dummy and then add another axis for to realize the opening and the closing of the fingers. Could be correct? Can I realize this? Any suggestion or help? -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
2011/11/17 Francesca Sca fancy_...@yahoo.it: Viesturs wrote: Genserkins will treat C as a rotary axis. It is binded into all those matrix conversions, jacobian functions and other stuff that I do not fully understand. IMHO, if You want to control the gripper, it should be anything but XYZABC. I agree with Andrew that adding U, V or W might be the way to go. On the other hand, adding that to genserkins does not seem very easy (at least for me). I have read a post of Alex Joni (the developer of genserkins) where he said that this module works at least 6 axis. If the machine has fewer, I need to set the others as dummy. So the solution could be using genserkins for 5 axis and 1 dummy and then add another axis for to realize the opening and the closing of the fingers. Could be correct? Can I realize this? Any suggestion or help? Yes, that is correct. Genserkins does calcs for 6 joints. If the actual robot has fewer, then dummy joints need to be defined to make up 6 joints for genserkins. If You need some extra joint, then it has to be added separately. What I understand from genserkins, it is coded for 6 joints, so the 7th joint has to be added in genserkins code and that is why I feel it not to be easy task. You did not answer, how You want to operate the gripper (just open/close or control, how much and how fast does it grab), so it is hard to tell, if that can be done in HAL. Sorry, I cannot help with genserkins, because I myself need help with the genserkins :)) Viesturs -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Viesturs wrote: Yes, that is correct. Genserkins does calcs for 6 joints. If the actual robot has fewer, then dummy joints need to be defined to make up 6 joints for genserkins. How I can make an axis dummy? for example the C one? If You need some extra joint, then it has to be added separately. What I understand from genserkins, it is coded for 6 joints, so the 7th joint has to be added in genserkins code and that is why I feel it not to be easy task. I don't want that the added axis take a part of the kinematics. I would that it works separatly. It possible make this? You did not answer, how You want to operate the gripper (just open/close or control, how much and how fast does it grab), so it is hard to tell, if that can be done in HAL. Sorry, I cannot help with genserkins, because I myself need help with the genserkins :)) Both the ways are ok for me. I think that I could control the axis that moves the fingers separatly from kinematic genserkins, I would have problems anymore. Genserkins is a nice problem for many people :p -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
2011/11/17 Francesca Sca fancy_...@yahoo.it: Viesturs wrote: Yes, that is correct. Genserkins does calcs for 6 joints. If the actual robot has fewer, then dummy joints need to be defined to make up 6 joints for genserkins. How I can make an axis dummy? for example the C one? I think - define DH parameters so that it matches the actual orientation of Your tool and do not attach any pwmgen/stepgen to it. You did not answer, how You want to operate the gripper (just open/close or control, how much and how fast does it grab), so it is hard to tell, if that can be done in HAL. Sorry, I cannot help with genserkins, because I myself need help with the genserkins :)) Both the ways are ok for me. I think that I could control the axis that moves the fingers separatly from kinematic genserkins, I would have problems anymore. Then there is very nice way to solve it: Use mux2 and limit3 components: Mux2.sel pin should be the open/close command (can be driven from g-code, if linked to spindle or coolant on/off HAL pins), mux2.in0 and mux2.in1 should be stepgen positions, when gripper is closed and open. Link mux2.out to limit3 input, set acceleration and velocity limits in limit3 and link limit3 output to stepgen pos-cmd input. Genserkins is a nice problem for many people :p No, I think You are wrong. Genserkins is extremely powerful, where it is applicable. I would say that genserkins is the reason, why EMC can beat majority of commercial robotic arm controllers in terms of ability to accept normal g-code - AFAIK all the robots need special CAM postprocessors, which convert Cartesian commands into motori position commands, so the code is not understandable by the operator. The problem with genserkins is customizing it, because it is very complex uses very advanced math functions, like jacobian. I think that I did everything needed for genserkins to work with linear joints, but I need some help with testing it, because it does not behave really the way I would expect it, but I am having difficulties understanding, how to debug it. Viesturs -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Viesturs wrote: Then there is very nice way to solve it: Use mux2 and limit3 components: Mux2.sel pin should be the open/close command (can be driven from g-code, if linked to spindle or coolant on/off HAL pins), mux2.in0 and mux2.in1 should be stepgen positions, when gripper is closed and open. Link mux2.out to limit3 input, set acceleration and velocity limits in limit3 and link limit3 output to stepgen pos-cmd input. You can explain me better this? Which are the right lines that I must add to my .hal file? No, I think You are wrong. Genserkins is extremely powerful, where it is applicable. The problem with genserkins is customizing it, because it is very complex uses very advanced math functions, like jacobian. I think the same things. Genserkins is very powerful but also very complex for people like me that aren't so expert! -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 17 November 2011 09:59, Francesca Sca fancy_...@yahoo.it wrote: Yes, that is correct. Genserkins does calcs for 6 joints. If the actual robot has fewer, then dummy joints need to be defined to make up 6 joints for genserkins. How I can make an axis dummy? for example the C one? This is one of those situations where it is important to be very clear about the distinction between Joints and Axes. genserkins assumes 6 joints (ie 6 motors) and also 6 axes (XYZABC). Whilst you could change the INI file to accept U, V or W axis words in the G-code (The COORDINATES= line) genserkins does not pass through this value to an axis.N.motor-pos-cmd pin. This might be seen as something of an oversight, or there might be an excellent reason... I think that the easiest solution might be to use M67 to send position commands out of the G-code to a HAL pin, and link that direct to a stepgen in HAL. I think that, in most cases, you can use the stepgen accell and velocity limits to control the motion. Homing might have to be a rather crude stall-the-motor-on-the-end-stops. Alternatively, it is probably possible to modify genserkins to pass-through UV and W in the same way as trivkins does. (line 357 onwards for forward kins, I can't immediately see where to do it for inverse kins) -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
2011/11/17 Francesca Sca fancy_...@yahoo.it: Viesturs wrote: Then there is very nice way to solve it: Use mux2 and limit3 components: Mux2.sel pin should be the open/close command (can be driven from g-code, if linked to spindle or coolant on/off HAL pins), mux2.in0 and mux2.in1 should be stepgen positions, when gripper is closed and open. Link mux2.out to limit3 input, set acceleration and velocity limits in limit3 and link limit3 output to stepgen pos-cmd input. You can explain me better this? Which are the right lines that I must add to my .hal file? You will have to do some reading to understand, what You have to do in the HAL file. My idea is to use mux2 and limit3 components to control the stepper motor of the gripper. http://gnipsel.com/emc2/html2.5/man/man9/mux2.9.html The way mux2 works: mux2.n.out = mux2.n.in0, if mux2.n.sel = false mux2.n.out = mux2.n.in1, if mux2.n.sel = true Attach the mux2.n.sel pin to open/close command and set mux2.n.in0 and mux2.n.in1 values to stepper motor positions that correspond to gripper being closed or open. Using limit3 will let You set the acceleration and velocity for the stepper motor easily. http://gnipsel.com/emc2/html2.5/man/man9/limit3.9.html Viesturs -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-novd2d ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
I solved the problem with the world mode when I'm using genserkins module. The main problems were the latency of my computer and some home setting wrong. But now I have another problem. I have set the D-H parameters of my robot but unlike Puma my robot has a hand and a stepper motor that controls the opening and closing of the fingers. Using the inverse kinematics I can't to control the opening and closing of fingers. How can I do this? any suggestions? -- RSA(R) Conference 2012 Save $700 by Nov 18 Register now http://p.sf.net/sfu/rsa-sfdev2dev1 ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
2011/11/16 Francesca Sca fancy_...@yahoo.it I solved the problem with the world mode when I'm using genserkins module. The main problems were the latency of my computer and some home setting wrong. But now I have another problem. I have set the D-H parameters of my robot but unlike Puma my robot has a hand and a stepper motor that controls the opening and closing of the fingers. Using the inverse kinematics I can't to control the opening and closing of fingers. How can I do this? any suggestions? If you want to completely control the fingers angle, you can assign another axis for them. It might be W if you already have XYZABC. I guess, you should add the axis to your HAL file and genserkins. It requires no kinematic transformation, just add the direct connection. Andrew -- RSA(R) Conference 2012 Save $700 by Nov 18 Register now http://p.sf.net/sfu/rsa-sfdev2dev1 ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Andrew wrote: If you want to completely control the fingers angle, you can assign another axis for them. It might be W if you already have XYZABC. I guess, you should add the axis to your HAL file and genserkins. It requires no kinematic transformation, just add the direct connection. My axis C is associated to the opening and closing of fingers. So I should using only 5 axes for the genserkins module and exclude the last one C to the kinematic trasformation? Could be correct? It is possible using genserkins for only 5 axes? What I should change? -- RSA(R) Conference 2012 Save $700 by Nov 18 Register now http://p.sf.net/sfu/rsa-sfdev2dev1 ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
Viesturs Lacis wrote: Hello, Franscesca! I have a question about genserkins that is unrelated to Your problem: The thing is that I tried to add also linear joints in it, but it seems that it is not working correctly. Please let me know, if You have a chance and spare time to test it - either in a simulated machine (preferrably with linear joints) or on Your robot arm (though it has only rotary joints). Genserkins.c and genserkins.h files are here: http://www.cutting.lv/fileadmin/user_upload/genserkins.c http://www.cutting.lv/fileadmin/user_upload/genserkins.h I'm sorry, I can't help you because genserkins doesn't work correctly on my pc also!! Andy pugh wrote: If you are using the Axis interface then you can see the value of the parameter in Machine-Show Hal Config (or perhaps Mostra configurazione HAL) and look at the parameter genserkins.max-iterations. You can change the value in the same window by typing setp ganserkin.max-iterations 100 If you find a value that works, then you can put that same line in your HAL file. I don't find the parameter genserkin.max-iterations in Hal Config. If I put this line setp ganserkin.max-iterations 100 in hal file, Emc2 gives an error because It isn't found this pin. So I really don't know why puma560-configuration and then genserkins doesn't work in world mode on all my computers ( I test these on 3 computers!!) also just for simulation!!! So there is something that I don't understand! -- RSA(R) Conference 2012 Save $700 by Nov 18 Register now http://p.sf.net/sfu/rsa-sfdev2dev1 ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 9 November 2011 09:44, Francesca Sca fancy_...@yahoo.it wrote: I don't find the parameter genserkin.max-iterations in Hal Config. It should be under parameters is that where you looked? If I put this line setp ganserkin.max-iterations 100 in hal file, Emc2 gives an error because It isn't found this pin. I am assuming you spelt it correctly? It has to be exactly genserkins.max-iterations I don't know for a fact that the pin is created, but the code to create it is in the kinematics file. -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- RSA(R) Conference 2012 Save $700 by Nov 18 Register now http://p.sf.net/sfu/rsa-sfdev2dev1 ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
are there any quite simple objective premises that form a basis for evaluating statements? --- On Wed, 11/9/11, andy pugh bodge...@gmail.com wrote: From: andy pugh bodge...@gmail.com Subject: Re: [Emc-users] problem with genserkins To: Francesca Sca fancy_...@yahoo.it, Enhanced Machine Controller (EMC) emc-users@lists.sourceforge.net Date: Wednesday, November 9, 2011, 3:00 AM On 9 November 2011 09:44, Francesca Sca fancy_...@yahoo.it wrote: I don't find the parameter genserkin.max-iterations in Hal Config. It should be under parameters is that where you looked? If I put this line setp ganserkin.max-iterations 100 in hal file, Emc2 gives an error because It isn't found this pin. I am assuming you spelt it correctly? It has to be exactly genserkins.max-iterations I don't know for a fact that the pin is created, but the code to create it is in the kinematics file. -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- RSA(R) Conference 2012 Save $700 by Nov 18 Register now http://p.sf.net/sfu/rsa-sfdev2dev1 ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users -- RSA(R) Conference 2012 Save $700 by Nov 18 Register now http://p.sf.net/sfu/rsa-sfdev2dev1 ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
andy pugh wrote: ERR kI - compute_jinv (joints: %f %f %f %f %f %f), (iterations=0) Looking at the source-code that error indicates that the inversion of the matrix has failed. It might mean that your DH parameters are in some way inconsistent, or possibly just that the motor position is ambiguous. Is that the actual error message? All those %f entries should be printing out as joint positions. I don't resolve my problem yet! :( I thought that this error ERR kI - compute_jinv (joints: %f %f %f %f %f %f), (iterations=0) could be mean that I didn't set the number of iterations that were used to compute the inverse kinematics. The genserkins module request a pin for this. It is correct? How I can set this? from genserkins.h and genserkins.c: TODO: * make number of joints a loadtime parameter * add HAL pins for all settable parameters, including joint type: ANGULAR / LINEAR * add HAL pins for debug data (num_iterations) * add HAL pins for ULAPI compiled version hal_s32_t iterations; /*! How many iterations were actually used to compute the inverse kinematics. */ hal_s32_t max_iterations; /*! Number of iterations after which to give up and report an error. */ -- RSA(R) Conference 2012 Save $700 by Nov 18 Register now http://p.sf.net/sfu/rsa-sfdev2dev1 ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 8 November 2011 09:44, Francesca Sca fancy_...@yahoo.it wrote: could be mean that I didn't set the number of iterations that were used to compute the inverse kinematics. The genserkins module request a pin for this. It is correct? How I can set this? It looks like a parameter is created to set the max iterations, but I think it is initialised to 100. (for reference, the HAL parameter is created in line 612) hal_s32_t iterations; /*! How many iterations were actually used to compute the inverse kinematics. */ hal_s32_t max_iterations; /*! Number of iterations after which to give up and report an error. */ If you are using the Axis interface then you can see the value of the parameter in Machine-Show Hal Config (or perhaps Mostra configurazione HAL) and look at the parameter genserkins.max-iterations. You can change the value in the same window by typing setp ganserkin.max-iterations 100 If you find a value that works, then you can put that same line in your HAL file. -- atp The idea that there is no such thing as objective truth is, quite simply, wrong. -- RSA(R) Conference 2012 Save $700 by Nov 18 Register now http://p.sf.net/sfu/rsa-sfdev2dev1 ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
andy pugh wrote: Odd. Seb tried the 560 config in a Sim version and got a number of errors but none in a realtime installation. This is odd, as things are expected to work just the same. Was this a fresh install from the LiveCD? My LiveCD is the version 2.4.3. I tried to run EMC2 from LiveCd and the puma560 configuration doesn't work yet. So I thought to use another pc to verify. I used the LiveCD and with this pc puma560 configuration works correctly. So the problem could be my pcSome suggestions? Should I re-install ubuntu? This is so odd -- All of the data generated in your IT infrastructure is seriously valuable. Why? It contains a definitive record of application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-d2dcopy2 ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On Oct 7, 2011, at 09:35 , Francesca Sca wrote: andy pugh wrote: Odd. Seb tried the 560 config in a Sim version and got a number of errors but none in a realtime installation. This is odd, as things are expected to work just the same. Was this a fresh install from the LiveCD? My LiveCD is the version 2.4.3. I tried to run EMC2 from LiveCd and the puma560 configuration doesn't work yet. So I thought to use another pc to verify. I used the LiveCD and with this pc puma560 configuration works correctly. So the problem could be my pcSome suggestions? Should I re-install ubuntu? This is so odd…. Try running memtest on the machine that's having trouble. I think it's one of the boot options on the Live CD. Also maybe try running latency-test on it and see if the numbers are reasonable. -- Sebastian Kuzminsky -- All of the data generated in your IT infrastructure is seriously valuable. Why? It contains a definitive record of application performance, security threats, fraudulent activity, and more. Splunk takes this data and makes sense of it. IT sense. And common sense. http://p.sf.net/sfu/splunk-d2dcopy2 ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
andy pugh wrote: I tried the puma560 config and it appeared to work for me. Are you running in a sim or a realtime installation? What version of EMC2? I have a realtime installation and the version of EMC2 is 2.4.6 -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity and more. Splunk takes this data and makes sense of it. Business sense. IT sense. Common sense. http://p.sf.net/sfu/splunk-d2dcopy1 ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 6 October 2011 19:02, Francesca Sca fancy_...@yahoo.it wrote: I tried the puma560 config and it appeared to work for me. Are you running in a sim or a realtime installation? What version of EMC2? I have a realtime installation and the version of EMC2 is 2.4.6 Odd. Seb tried the 560 config in a Sim version and got a number of errors but none in a realtime installation. This is odd, as things are expected to work just the same. Was this a fresh install from the LiveCD? -- atp Torque wrenches are for the obedience of fools and the guidance of wise men -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity and more. Splunk takes this data and makes sense of it. Business sense. IT sense. Common sense. http://p.sf.net/sfu/splunk-d2dcopy1 ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
andy pugh wrote: Looking at the source-code that error indicates that the inversion of the matrix has failed. It might mean that your DH parameters are in some way inconsistent, or possibly just that the motor position is ambiguous. Is that the actual error message? All those %f entries should be printing out as joint positions. I don't know if this is the actual error. I have the same problem also with puma560 configuration that uses genserkins! In puma example the d-h parameters are correct then I don't think that the parameters are the problem. What else could be? -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity and more. Splunk takes this data and makes sense of it. Business sense. IT sense. Common sense. http://p.sf.net/sfu/splunk-d2dcopy1 ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 5 October 2011 10:59, Francesca Sca fancy_...@yahoo.it wrote: I don't know if this is the actual error. I have the same problem also with puma560 configuration that uses genserkins! In puma example the d-h parameters are correct then I don't think that the parameters are the problem. What else could be? I tried the puma560 config and it appeared to work for me. Are you running in a sim or a realtime installation? What version of EMC2? -- atp Torque wrenches are for the obedience of fools and the guidance of wise men -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity and more. Splunk takes this data and makes sense of it. Business sense. IT sense. Common sense. http://p.sf.net/sfu/splunk-d2dcopy1 ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
[Emc-users] problem with genserkins
Hi Emc users, I have a 6dof robot and I would like to use genserkins module for the kinematics of my robot. I set up the D-H parameters but the robot doesn't work in world mode. Also the puma 560 configuration (that uses genserkins module) doesn't work while I have no problem with puma configuration and pumakins. So, which could be the problem with genserkins? An showed error is: ERR kI - compute_jinv (joints: %f %f %f %f %f %f), (iterations=0). Some help? Thanks! -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity and more. Splunk takes this data and makes sense of it. Business sense. IT sense. Common sense. http://p.sf.net/sfu/splunk-d2dcopy1 ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] problem with genserkins
On 3 October 2011 10:00, Francesca Sca fancy_...@yahoo.it wrote: ERR kI - compute_jinv (joints: %f %f %f %f %f %f), (iterations=0) Looking at the source-code that error indicates that the inversion of the matrix has failed. It might mean that your DH parameters are in some way inconsistent, or possibly just that the motor position is ambiguous. Is that the actual error message? All those %f entries should be printing out as joint positions. -- atp Torque wrenches are for the obedience of fools and the guidance of wise men -- All the data continuously generated in your IT infrastructure contains a definitive record of customers, application performance, security threats, fraudulent activity and more. Splunk takes this data and makes sense of it. Business sense. IT sense. Common sense. http://p.sf.net/sfu/splunk-d2dcopy1 ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users